Skip to content

Commit

Permalink
add @brief and explain comments
Browse files Browse the repository at this point in the history
  • Loading branch information
ike-kazu committed May 27, 2024
1 parent 28b1f9f commit 00034f9
Show file tree
Hide file tree
Showing 5 changed files with 32 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ class VelodyneDecoder : public VelodyneScanDecoder
}

int pointsPerPacket() { return BLOCKS_PER_PACKET * CHANNELS_PER_BLOCK; }

void reset_pointcloud(size_t n_pts, double time_stamp)
{
// scan_pc_.reset(new NebulaPointCloud);
Expand Down Expand Up @@ -286,7 +286,7 @@ class VelodyneDecoder : public VelodyneScanDecoder
sensor_.getAzimuthCorrected(azimuth, azimuth_diff, firing_seq, firing_order);

// Condition added to avoid calculating points which are not in the interesting
// defined area (cloud_min_angle < area < cloud_max_angle).
// defined area (cloud_min_angle <= area <= cloud_max_angle).
if (true) {
// convert polar coordinates to Euclidean XYZ.
const float cos_vert_angle = corrections.cos_vert_correction;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,16 @@ namespace drivers
class VelodyneSensor
{
public:
// To ignore an empty data blocks which is created by only VLS128 dual return mode case
/// @brief eash VLP lidars packat structure in user manual. If you know details, see commens in each <vlp_list>.hpp file.

Check warning on line 14 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (eash)
virtual int getNumPaddingBlocks(bool /* dual_return */) { return 0; }

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

// calculate the corrected azimuth from each firing timing.
/// @brief each VLP calculating code sample in user manual. If you know details, see commens in each <vlp_list>.hpp file.
virtual uint16_t getAzimuthCorrected(
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) = 0;
};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,12 @@ namespace drivers
class VLP16 : public VelodyneSensor
{
public:
/// @brief fomula from VLP16 User manual in p.64

Check warning on line 12 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp_16.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fomula)
/// @param azimuth Azimuth angle
/// @param azimuth_diff Azimuth difference
/// @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)
{
Expand All @@ -20,6 +26,7 @@ class VLP16 : public VelodyneSensor
return static_cast<uint16_t>(round(azimuth_corrected)) % 36000;
}

// Choose the correct azimuth from the 2 azimuthes

Check warning on line 29 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp_16.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (azimuthes)
uint16_t getTrueRotation(uint16_t azimuth_corrected, uint16_t current_block_rotation)
{
return azimuth_corrected;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@ namespace drivers
class VLP32 : public VelodyneSensor
{
public:
// calculate and stack the firing timing for each laser timeing
/// @brief laser timing for VLP32 from VLP32 User manual in p.61
bool fillAzimuthCache()
{
for (uint8_t i = 0; i < 16; i++) {
Expand All @@ -17,6 +19,11 @@ class VLP32 : public VelodyneSensor
return true;
}

/// @brief fomula from VLP32 User manual in p.62

Check warning on line 22 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp_32.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fomula)
/// @param azimuth Azimuth angle
/// @param azimuth_diff Azimuth difference between a current azimuth and a next azimuth
/// @param firing_order Firing order
/// @return Corrected azimuth
uint16_t getAzimuthCorrected(
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order)
{
Expand All @@ -25,6 +32,7 @@ class VLP32 : public VelodyneSensor
return static_cast<uint16_t>(round(azimuth_corrected)) % 36000;
}

// Choose the correct azimuth from the 2 azimuthes

Check warning on line 35 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vlp_32.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (azimuthes)
uint16_t getTrueRotation(uint16_t azimuth_corrected, uint16_t current_block_rotation)
{
return current_block_rotation;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,16 @@ namespace drivers
class VLS128 : public VelodyneSensor
{
public:
// To ignore an empty data blocks in VLS128 case
/// @brief VLS128 Dual return mode data structure in VLS128 User manual p.57
int getNumPaddingBlocks(bool dual_return)
{
if (dual_return) return 4;
return 0;
}

// calculate and stack the firing timing for each laser timeing
/// @brief laser timing for VLS128 from VLS128 User manual in p.61
bool fillAzimuthCache()
{
for (uint8_t i = 0; i < 16; i++) {
Expand All @@ -23,6 +27,11 @@ class VLS128 : public VelodyneSensor
return true;
}

/// @brief fomula from VLS128 User manual in p.65

Check warning on line 30 in nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/vls_128.hpp

View workflow job for this annotation

GitHub Actions / spell-check-differential

Unknown word (fomula)
/// @param azimuth Azimuth angle
/// @param azimuth_diff Azimuth difference
/// @param firing_order Firing order
/// @return Corrected azimuth
uint16_t getAzimuthCorrected(
uint16_t azimuth, float azimuth_diff, int /* firing_sequence */, int firing_order)
{
Expand Down

0 comments on commit 00034f9

Please sign in to comment.