diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp index 56da1e96..285c5e89 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_generic_decoder.hpp @@ -5,9 +5,7 @@ #include #include - #include - #include #include #include @@ -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); diff --git a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp index 9326a119..a6a1a1ed 100644 --- a/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp +++ b/nebula_decoders/include/nebula_decoders/nebula_decoders_velodyne/decoders/velodyne_sensor.hpp @@ -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 .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 \ No newline at end of file