praveen-palanisamy / multiple-object-tracking-lidar

C++ implementation to Detect, track and classify multiple objects using LIDAR scans or point cloud
MIT License
787 stars 229 forks source link

How to use LaserScan messages instead of PointCloud2? #28

Closed chumingqian closed 4 years ago

chumingqian commented 4 years ago

Closing the issue as the question was answered. Reopen if you need more info. Thanks!

Originally posted by @praveen-palanisamy in https://github.com/praveen-palanisamy/multiple-object-tracking-lidar/issues/9#issuecomment-525173447

chumingqian commented 4 years ago

Hi,palanisamy: @praveen-palanisamy thanks for your sharing, and i have a question.
In src/main.cpp line 21 : #include <sensor_msgs/PointCloud2.h> data type is pointCloud2.msg. However , my data type is a LaserScan.msg. When i run the code, i got the error sth about datatype mistake, how should i solve this , could you give a guide , thanks in advance .

pointCloud2 laserScan

praveen-palanisamy commented 4 years ago

Hi @chumingqian , You can use the laser_geometry ROS package to convert your LaserScan messages to PointCloud2 message. Here's a code example:

laser_geometry::LaserProjection projector_;

void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_in)
{
  sensor_msgs::PointCloud2 point_cloud;
  projector_.projectLaser(*scan_in, point_cloud);

  // You can now use point_cloud
}
chumingqian commented 4 years ago

Hi @chumingqian , You can use the laser_geometry ROS package to convert your LaserScan messages to PointCloud2 message. Here's a code example:

laser_geometry::LaserProjection projector_;

void scanCallback (const sensor_msgs::LaserScan::ConstPtr& scan_in)
{
  sensor_msgs::PointCloud2 point_cloud;
  projector_.projectLaser(*scan_in, point_cloud);

  // You can now use point_cloud
}

It worked ,thank you so much!!!