ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You are correct. The data you get from your sensors are in their own frame of reference. For distance / range measurements, its often a good idea to have them in the frame of reference of your robot; usually base_link
.
Fortunately ROS provides the tf library for this purpose. You can find more information here.
I highly recommend you go through their tutorials but the one you are looking for is a tf listener python / C++.
Once you have this transform, you can apply it to your scan. Unfortunately laserscans aren't very easy to work with and I'd suggest you convert your scan to a PointCloud2 msg and use the features PCL has to offer.
2 | No.2 Revision |
You are correct. The data you get from your sensors are in their own frame of reference. For distance / range measurements, its often a good idea to have them in the frame of reference of your robot; usually base_link
.
Fortunately ROS provides the tf library for this purpose. You can find more information here.
I highly recommend you go through their tutorials but the one you are looking for is a tf listener python / C++.
Once you have this transform, you can apply it to your scan. Unfortunately laserscans aren't very easy to work with and I'd suggest you convert your scan to a PointCloud2 msg and use the features PCL has to offer.
EDIT: Based on your LiDAR scan msg type, here are my suggestions:
Use the laserscan_to_pointcloud
package to convert your laserscan
to PointCloud2
type. You can just include this into your launch file:
<node pkg="pointcloud_to_laserscan" type="laserscan_to_pointcloud_node" name="laserscan_to_pointcloud">
<remap from="scan_in" to="/scan"/>
<remap from="cloud" to="/hokuyo_cloud"/>
</node>
Then, in your LiDAR callback, convert from ROS type to PCL type, lookup tf and apply it to your data. This is standard pipeline
void CloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud_in)
{
// copy point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*cloud_in, *cloud);
// Transform point cloud
try {
transform_stamped = tf_buffer.lookupTransform("base_link",
cloud_in->header.frame_id,
ros::Time(0),
ros::Duration(1));
} catch (tf2::TransformException &ex) {
ROS_ERROR("%s", ex.what());
return;
}
// apply transform to point cloud
Eigen::Affine3d pc_to_base_link = tf2::transformToEigen(transform_stamped);
pcl::transformPointCloud(*cloud, *cloud,
pc_to_base_link);
/*
Use cloud as you normally would
*/
// convert back to ROS
sensor_msgs::PointCloud2 cloud_out;
pcl::toROSMsg(*cloud, cloud_out);
cloud_out.header.frame_id = cloud_in->header.frame_id;
cloud_out.header.stamp = ros::Time::now();
// publish
publisher.publish(cloud_out);
}
3 | No.3 Revision |
You are correct. The data you get from your sensors are in their own frame of reference. For distance / range measurements, its often a good idea to have them in the frame of reference of your robot; usually base_link
.
Fortunately ROS provides the tf library for this purpose. You can find more information here.
I highly recommend you go through their tutorials but the one you are looking for is a tf listener python / C++.
Once you have this transform, you can apply it to your scan. Unfortunately laserscans aren't very easy to work with and I'd suggest you convert your scan to a PointCloud2 msg and use the features PCL has to offer.
EDIT: Based on your LiDAR scan msg type, here are my suggestions:
Use the laserscan_to_pointcloud
package to convert your laserscan
to PointCloud2
type. You can just include this into your launch file:
<node pkg="pointcloud_to_laserscan" type="laserscan_to_pointcloud_node" name="laserscan_to_pointcloud">
<remap from="scan_in" to="/scan"/>
to="/<your scan topic>"/>
<remap from="cloud" to="/hokuyo_cloud"/>
to="/<your cloud topic>"/>
</node>
Then, in your LiDAR callback, convert from ROS type to PCL type, lookup tf and apply it to your data. This is standard pipeline
void CloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud_in)
{
// copy point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*cloud_in, *cloud);
// Transform point cloud
try {
transform_stamped = tf_buffer.lookupTransform("base_link",
cloud_in->header.frame_id,
ros::Time(0),
ros::Duration(1));
} catch (tf2::TransformException &ex) {
ROS_ERROR("%s", ex.what());
return;
}
// apply transform to point cloud
Eigen::Affine3d pc_to_base_link = tf2::transformToEigen(transform_stamped);
pcl::transformPointCloud(*cloud, *cloud,
pc_to_base_link);
/*
Use cloud as you normally would
*/
// convert back to ROS
sensor_msgs::PointCloud2 cloud_out;
pcl::toROSMsg(*cloud, cloud_out);
cloud_out.header.frame_id = cloud_in->header.frame_id;
cloud_out.header.stamp = ros::Time::now();
// publish
publisher.publish(cloud_out);
}
4 | No.4 Revision |
You are correct. The data you get from your sensors are in their own frame of reference. For distance / range measurements, its often a good idea to have them in the frame of reference of your robot; usually base_link
.
Fortunately ROS provides the tf library for this purpose. You can find more information here.
I highly recommend you go through their tutorials but the one you are looking for is a tf listener python / C++.
Once you have this transform, you can apply it to your scan. Unfortunately laserscans aren't very easy to work with and I'd suggest you convert your scan to a PointCloud2 msg and use the features PCL has to offer.
EDIT: Based on your LiDAR scan msg type, here are my suggestions:
Use the laserscan_to_pointcloud
package to convert your laserscan
to PointCloud2
type. You can just include this into your launch file:
<node pkg="pointcloud_to_laserscan" type="laserscan_to_pointcloud_node" name="laserscan_to_pointcloud">
<remap from="scan_in" to="/<your scan topic>"/>
<remap from="cloud" to="/<your cloud topic>"/>
</node>
Then, in your LiDAR callback, convert from ROS type to PCL type, lookup tf and apply it to your data. This is standard a simple pipeline
void CloudCallback(const sensor_msgs::PointCloud2ConstPtr &cloud_in)
{
// copy point cloud
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
pcl::fromROSMsg(*cloud_in, *cloud);
// Transform point cloud
try {
transform_stamped = tf_buffer.lookupTransform("base_link",
cloud_in->header.frame_id,
ros::Time(0),
ros::Duration(1));
} catch (tf2::TransformException &ex) {
ROS_ERROR("%s", ex.what());
return;
}
// apply transform to point cloud
Eigen::Affine3d pc_to_base_link = tf2::transformToEigen(transform_stamped);
pcl::transformPointCloud(*cloud, *cloud,
pc_to_base_link);
/*
Use cloud as you normally would
*/
// convert back to ROS
sensor_msgs::PointCloud2 cloud_out;
pcl::toROSMsg(*cloud, cloud_out);
cloud_out.header.frame_id = cloud_in->header.frame_id;
cloud_out.header.stamp = ros::Time::now();
// publish
publisher.publish(cloud_out);
}