ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

pcd file to PointCloud visualization problem in Rviz [closed]

asked 2018-06-26 07:26:12 -0500

zeynep gravatar image

updated 2018-06-26 09:23:56 -0500

Hello, I have loaded a pcd file and converted it to sensor_msgs::PointCloud2 message type. When I add this point cloud to rviz screen, it needs to be rotated and translated.. my point cloud coordinate frame "pcl" and fixed frame is "map".. I dont know how to make transformation from pcl Coor. Frame to Map with tf/static_transform_publisher to visualize the point cloud properly..

this is my code:

int main(int argc, char **argv)
{

  // Initialize ROS
  ros::init (argc, argv, "my_pc_pub");

  ros::NodeHandle nh;

  ros::Rate loop_rate(0.1);

  pcl::PCLPointCloud2 pcl_pc;

  sensor_msgs::PointCloud2 msg;

  sensor_msgs::PointCloud2 msg2;

  tf::TransformListener tf_obj;

  // Create a ROS publisher for the output point cloud

  ros::Publisher pub = nh.advertise<pcl::PointCloud<pcl::PointXYZ>>("my_pc", 1);

  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);

  if (pcl::io::loadPCDFile<pcl::PointXYZ> ("/home/largo/ws/table_scene_lms400_downsampled.pcd",*cloud) == -1)
   {
     PCL_ERROR("Could not read file");
     return (-1);
   }


  std::cout<<"Loaded"
           <<cloud->width * cloud->height
           <<" data points from test_pcd.pcd with the following fields"
           <<std::endl;

  pcl::toPCLPointCloud2(*cloud, pcl_pc);

  while (ros::ok())
    {
      pcl_conversions::fromPCL(pcl_pc, msg);

      msg.header.frame_id="pcl";
      msg.header.stamp = ros::Time::now();
     pcl_ros::transformPointCloud("map",msg, msg2, tf_obj) ;
     pub.publish(msg2); //my_pc topic

      ros::spinOnce();
      loop_rate.sleep();

    }

    return  0;
}
edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by zeynep
close date 2018-08-23 16:04:06.886725

Comments

Can you please describe the behaviour your code produces? Does it compile? Does it cause a runtime error or does not perform the way you expect?

PeteBlackerThe3rd gravatar image PeteBlackerThe3rd  ( 2018-06-26 09:28:53 -0500 )edit

it runs and produces sensor_msgs::PointCloud2 messages, frame_id "pcl" When I visualize this message from rviz , i choose fixed_frame=pcl and rviz view type top-down Orthographic view, it is ok but i want it to be transformed according to map

zeynep gravatar image zeynep  ( 2018-06-26 09:47:56 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-06-26 20:36:34 -0500

You need to provide the tf transformation between the map link and the plc link. Take a look at http://wiki.ros.org/tf#static_transfo... :

static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period_in_ms

For example, to have the pointcloud appear 1 meter above the map and upside-down, you should execute the following before running your node:

rosrun tf static_transform_publisher 0 0 1.0 3.141592654 0 0 map plc 100

Then in Rviz you should be able to select "map" as the <fixed_frame> and see the PointCloud

I hope this helps

edit flag offensive delete link more

Comments

it is ok. Thank you for your help

zeynep gravatar image zeynep  ( 2018-06-27 05:49:49 -0500 )edit

Question Tools

Stats

Asked: 2018-06-26 07:26:12 -0500

Seen: 1,439 times

Last updated: Jun 26 '18