Skip to content

Commit

Permalink
remove superfluous code
Browse files Browse the repository at this point in the history
  • Loading branch information
bgilby59 committed Jan 11, 2024
1 parent 638c532 commit 12077a8
Show file tree
Hide file tree
Showing 3 changed files with 2 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,6 @@ void Vlp16Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa
const float z_coord = distance * sin_vert_angle; // velodyne z
const uint8_t intensity = current_block.data[k + 2];

auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds();
last_block_timestamp_ = block_timestamp;

double point_time_offset = timing_offsets_[block][firing * 16 + dsr];
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,8 @@ void Vlp32Decoder::reset_overflow(double time_stamp)
// be relative to the overflow's packet timestamp
double new_timestamp_seconds =
scan_timestamp_ + 1e-9 * overflow_point.time_stamp - last_block_timestamp_;
overflow_point.time_stamp = static_cast<uint32_t>(new_timestamp_seconds < 0.0 ? 0.0 : 1e9 * new_timestamp_seconds);
overflow_point.time_stamp =
static_cast<uint32_t>(new_timestamp_seconds < 0.0 ? 0.0 : 1e9 * new_timestamp_seconds);

scan_pc_->points.emplace_back(overflow_point);
overflow_pc_->points.pop_back();
Expand Down Expand Up @@ -281,7 +282,6 @@ void Vlp32Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_pa

intensity = raw->blocks[i].data[k + 2];

auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds();
last_block_timestamp_ = block_timestamp;

const float focal_offset = 256 * (1 - corrections.focal_distance / 13100) *
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -282,11 +282,7 @@ void Vls128Decoder::unpack(const velodyne_msgs::msg::VelodynePacket & velodyne_p
const float y_coord = -(xy_distance * sin_rot_angle); // velodyne x
const float z_coord = distance * sin_vert_angle; // velodyne z
const uint8_t intensity = current_block.data[k + 2];
auto block_timestamp = rclcpp::Time(velodyne_packet.stamp).seconds();
last_block_timestamp_ = block_timestamp;
if (scan_timestamp_ < 0) {
scan_timestamp_ = block_timestamp;
}
double point_time_offset =
timing_offsets_[block / 4][firing_order + laser_number / 64];

Expand Down

0 comments on commit 12077a8

Please sign in to comment.