Skip to content

Commit

Permalink
chore(velodyne): fix compiler and clang-tidy errors after rebase
Browse files Browse the repository at this point in the history
Signed-off-by: Max SCHMELLER <[email protected]>
  • Loading branch information
mojomex committed Nov 18, 2024
1 parent 20a1e22 commit 1696281
Show file tree
Hide file tree
Showing 9 changed files with 417 additions and 334 deletions.

Large diffs are not rendered by default.

Original file line number Diff line number Diff line change
@@ -1,41 +1,51 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include <cstddef>
#include <cstdint>
#include <ctime>

namespace nebula
{
namespace drivers
{
namespace velodyne_packet
namespace nebula::drivers::velodyne_packet
{

/**
* Raw Velodyne packet constants and structures.
*/
static const int RAW_SCAN_SIZE = 3; // TODO: remove
static const int SCANS_PER_BLOCK = 32; // TODO: remove
static const int CHANNELS_PER_BLOCK = 32;
static const int g_raw_scan_size = 3; // TODO(ike-kazu): remove
static const int g_scans_per_block = 32; // TODO(ike-kazu): remove
static const int g_channels_per_block = 32;

static const double ROTATION_RESOLUTION = 0.01; // [deg]
static const uint16_t ROTATION_MAX_UNITS = 360 * 100u; // [deg/100]
static const double g_rotation_resolution = 0.01; // [deg]
static const uint16_t g_rotation_max_units = 360 * 100u; // [deg/100]

static const size_t RETURN_MODE_INDEX = 1204;
static const size_t g_return_mode_index = 1204;

/** @todo make this work for both big and little-endian machines */
static const uint16_t UPPER_BANK = 0xeeff;
static const uint16_t LOWER_BANK = 0xddff;
static const uint16_t g_upper_bank = 0xeeff;
static const uint16_t g_lower_bank = 0xddff;

/** Return Modes **/
static const uint16_t RETURN_MODE_STRONGEST = 55;
static const uint16_t RETURN_MODE_LAST = 56;
static const uint16_t RETURN_MODE_DUAL = 57;
static const uint16_t g_return_mode_strongest = 55;
static const uint16_t g_return_mode_last = 56;
static const uint16_t g_return_mode_dual = 57;

const int BLOCKS_PER_PACKET = 12;
const int PACKET_STATUS_SIZE = 4;
const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
const int POINTS_PER_PACKET = (SCANS_PER_PACKET * RAW_SCAN_SIZE);
const int g_blocks_per_packet = 12;
const int g_packet_status_size = 4;
const int g_scans_per_packet = (g_scans_per_block * g_blocks_per_packet);
const int g_points_per_packet = (g_scans_per_packet * g_raw_scan_size);

#pragma pack(push, 1)
/** \brief Raw Velodyne data block.
Expand All @@ -45,16 +55,17 @@ const int POINTS_PER_PACKET = (SCANS_PER_PACKET * RAW_SCAN_SIZE);
*
* use stdint.h types, so things work with both 64 and 32-bit machines
*/
struct raw_units{
struct raw_units
{
uint16_t distance;
uint8_t reflectivity;
};

struct raw_block_t
{
uint16_t flag; ///< UPPER_BANK or LOWER_BANK
uint16_t flag; ///< UPPER_BANK or LOWER_BANK
uint16_t rotation; ///< 0-35999, divide by 100 to get degrees
raw_units units[SCANS_PER_BLOCK];
raw_units units[g_scans_per_block];
};

/** \brief Raw Velodyne packet.
Expand All @@ -71,7 +82,7 @@ struct raw_block_t
*/
struct raw_packet_t
{
raw_block_t blocks[BLOCKS_PER_PACKET];
raw_block_t blocks[g_blocks_per_packet];
uint32_t timestamp;
uint16_t factory;
};
Expand All @@ -89,6 +100,4 @@ enum RETURN_TYPE {
DUAL_ONLY = 7
};

} // namespace hesai_packet
} // namespace drivers
} // namespace nebula
} // namespace nebula::drivers::velodyne_packet
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,6 @@
#include <cmath>
#include <cstdint>
#include <memory>
#include <string>
#include <tuple>
#include <vector>

Expand All @@ -44,9 +43,13 @@ class VelodyneScanDecoder
private:
size_t processed_packets_{0};
uint32_t prev_packet_first_azm_phased_{0};
bool has_scanned_{false};

static const size_t g_offset_first_azimuth = 2;
static const size_t g_offset_last_azimuth = 1102;
static const uint32_t g_degree_subdivisions = 100;

protected:
bool has_scanned_{false};
/// @brief Checks if the current packet completes the ongoing scan.
/// TODO: this has been moved from velodyne_hw_interface.cpp and is a temporary solution until
/// the Velodyne decoder uses the same structure as Hesai/Robosense
Expand Down Expand Up @@ -115,7 +118,7 @@ class VelodyneScanDecoder

/// @brief Virtual function for getting the flag indicating whether one cycle is ready
/// @return Readied
virtual bool hasScanned() = 0;
virtual bool has_scanned() = 0;

/// @brief Virtual function for getting the constructed point cloud
/// @return tuple of Point cloud and timestamp
Expand Down
Original file line number Diff line number Diff line change
@@ -1,39 +1,60 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once
#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_scan_decoder.hpp"

#include <cstdint>

namespace nebula
{
namespace drivers
namespace nebula::drivers
{
class VelodyneSensor
{
public:
/// @brief each VLP lidars packat structure in user manual. If you know details, see commens in each <vlp_list>.hpp file.
/// To ignore an empty data blocks which is created by only VLS128 dual return mode case
virtual int getNumPaddingBlocks(bool /* dual_return */) { return 0; }

/// @brief each VLP lidar laser timing in user manual. If you know details, see commens in each <vlp_list>.hpp file.
/// calculate and stack the firing timing for each laser timeing used in getAzimuthCorrected to calculate the corrected azimuth
virtual bool fillAzimuthCache() { return false; }
VelodyneSensor() = default;
VelodyneSensor(const VelodyneSensor &) = default;
VelodyneSensor(VelodyneSensor &&) = default;
VelodyneSensor & operator=(const VelodyneSensor &) = default;
VelodyneSensor & operator=(VelodyneSensor &&) = default;
virtual ~VelodyneSensor() = default;

/// @brief each VLP lidars packat structure in user manual. If you know details, see commens in
/// each <vlp_list>.hpp file. To ignore an empty data blocks which is created by only VLS128 dual
/// return mode case
virtual int get_num_padding_blocks(bool /* dual_return */) { return 0; }

/// @brief each VLP lidar laser timing in user manual. If you know details, see commens in each
/// <vlp_list>.hpp file. calculate and stack the firing timing for each laser timeing used in
/// getAzimuthCorrected to calculate the corrected azimuth
virtual bool fill_azimuth_cache() { return false; }

/// @brief VSL128User manual p. Packet structure
virtual uint getBank(uint bank, uint /* header */) { return bank; }
virtual uint32_t get_bank(uint32_t bank, uint32_t /* header */) { return bank; }

/// @brief each VLP calculating sample code and formula in user manual. If you know details, see commens in each <vlp_list>.hpp file.
/// calculate the corrected azimuth from each firing timing.
virtual uint16_t getAzimuthCorrected(
/// @brief each VLP calculating sample code and formula in user manual. If you know details, see
/// commens in each <vlp_list>.hpp file. calculate the corrected azimuth from each firing timing.
virtual uint16_t get_azimuth_corrected(
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) = 0;

/// @brief each VLP calculating sample code and formula in user manual. Check packet structure.
/// Get a correct firing order
virtual int getFiringOrder(int /* channels_per_block */, int /* scans_per_firing */) { return 0; }
virtual int get_firing_order(int /* channels_per_block */, int /* scans_per_firing */)
{
return 0;
}

/// @brief each VLP calculating sample code and formula in user manual. Check packet structure.
/// Get a correct channel number
virtual int getChannelNumber(int /* unit_idx */) { return 0; }

virtual int get_channel_number(int /* unit_idx */) { return 0; }
};
} // namespace drivers
} // namespace nebula
} // namespace nebula::drivers
Original file line number Diff line number Diff line change
@@ -1,9 +1,24 @@
// Copyright 2024 TIER IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#pragma once

#include "nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp"

namespace nebula
{
namespace drivers
#include <cmath>

namespace nebula::drivers
{

class VLP16 : public VelodyneSensor
Expand All @@ -15,33 +30,31 @@ class VLP16 : public VelodyneSensor
/// @param firing_sequence Firing sequence
/// @param firing_order Firing order
/// @return Corrected azimuth
uint16_t getAzimuthCorrected(
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order)
uint16_t get_azimuth_corrected(
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) override
{
float azimuth_corrected =
azimuth + (azimuth_diff *
((firing_order * VLP16_DSR_TOFFSET) + (firing_sequence * VLP16_FIRING_TOFFSET)) /
VLP16_BLOCK_DURATION);
((firing_order * vlp16_dsr_toffset) + (firing_sequence * vlp16_firing_toffset)) /
vlp16_block_duration);

return static_cast<uint16_t>(round(azimuth_corrected)) % 36000;
}

// Not succeed nebula_test on only VLP32 so add this function
// Choose the correct azimuth from the 2 azimuths
uint16_t getTrueRotation(uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
static uint16_t get_true_rotation(
uint16_t azimuth_corrected, uint16_t /* current_block_rotation */)
{
return azimuth_corrected;
}

int getFiringOrder(int channels, int scans_per_firing)
int get_firing_order(int channels, int scans_per_firing) override
{
return channels / scans_per_firing;
}

int getChannelNumber(int unit_idx)
{
return unit_idx % channels_per_firing_sequence;
}
int get_channel_number(int unit_idx) override { return unit_idx % channels_per_firing_sequence; }

constexpr static int num_maintenance_periods = 0;

Expand All @@ -60,11 +73,10 @@ class VLP16 : public VelodyneSensor
constexpr static double offset_packet_time = 0;

/** Special Defines for VLP16 support **/
constexpr static const int VLP16_FIRINGS_PER_BLOCK = 2;
constexpr static const int VLP16_SCANS_PER_FIRING = 16;
constexpr static const float VLP16_BLOCK_DURATION = 110.592f; // [µs]
constexpr static const float VLP16_DSR_TOFFSET = 2.304f; // [µs]
constexpr static const float VLP16_FIRING_TOFFSET = 55.296f; // [µs]
constexpr static const int vlp16_firings_per_block = 2;
constexpr static const int vlp16_scans_per_firing = 16;
constexpr static const float vlp16_block_duration = 110.592f; // [µs]
constexpr static const float vlp16_dsr_toffset = 2.304f; // [µs]
constexpr static const float vlp16_firing_toffset = 55.296f; // [µs]
};
} // namespace drivers
} // namespace nebula
} // namespace nebula::drivers
Loading

0 comments on commit 1696281

Please sign in to comment.