Skip to content

Commit

Permalink
arrange code
Browse files Browse the repository at this point in the history
  • Loading branch information
ike-kazu authored and mojomex committed Nov 18, 2024
1 parent 618f321 commit 20a1e22
Show file tree
Hide file tree
Showing 2 changed files with 9 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,7 @@

#include <velodyne_msgs/msg/velodyne_packet.hpp>
#include <velodyne_msgs/msg/velodyne_scan.hpp>

#include <angles/angles.h>

#include <array>
#include <cmath>
#include <utility>
Expand Down Expand Up @@ -215,7 +213,7 @@ class VelodyneDecoder : public VelodyneScanDecoder

for (int unit_idx = 0; unit_idx < velodyne_packet::CHANNELS_PER_BLOCK; ++unit_idx) {
uint16_t current_distance;
uint16_t other_distance;
uint16_t other_distance = 0;
int firing_seq = sensor_.getFiringOrder(unit_idx, SensorT::channels_per_firing_sequence);
int channel = sensor_.getChannelNumber(unit_idx);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,21 +19,21 @@ class VelodyneSensor
virtual bool fillAzimuthCache() { return false; }

/// @brief VSL128User manual p. Packet structure
virtual uint getBank(uint bank, uint header) { return bank; }
virtual uint getBank(uint bank, uint /* 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(
uint16_t azimuth, float azimuth_diff, int firing_sequence, int firing_order) = 0;

/// @brief each VLP calculating sample code and formula in user manual.
/// Choose the correct azimuth from the 2 azimuths
virtual int getFiringOrder(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 firing order
virtual int getFiringOrder(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; }

/// @brief each VLP calculating sample code and formula in user manual.
/// Choose the correct azimuth from the 2 azimuths
virtual int getChannelNumber(int unit_idx) { return 0; }

};
} // namespace drivers
} // namespace nebula

0 comments on commit 20a1e22

Please sign in to comment.