Skip to content

Commit

Permalink
velodyne_packet_pointcloud: Rest the pointer to the cloud in the proc…
Browse files Browse the repository at this point in the history
…essPacket function,as there is no call to the setup function of the base class in this case.
  • Loading branch information
judav25 committed Sep 24, 2024
1 parent de7bc05 commit e898503
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions velodyne_packet_pointcloud/src/unpacker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -109,10 +109,10 @@ namespace velodyne_packet_pointcloud
void
Unpacker::processPacket(const velodyne_msgs::VelodynePacket &packetMsg, const uint8_t return_mode)
{
// contents of the setup function in base class ( no scan message to pas to this function)
// contents of the setup function in base class ( no scan message to pass to this function)
set_return_mode(return_mode);


cloud.reset(new sensor_msgs::PointCloud2(cloud_template));
manage_tf_buffer();
packets_in_scan = 1; // must be ste to at least one
cloud->header.stamp = packetMsg.stamp;
Expand Down

0 comments on commit e898503

Please sign in to comment.