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

pointcloud_to_laserscan rotation of scan line

asked 2015-03-21 13:10:41 -0600

rnunziata gravatar image

updated 2015-03-23 17:57:03 -0600

I am running pointcloud_to_laserscan . When I display the pointcloud2 in rviz after rotation the camera frame is displays correctly along the rviz ground plane. However the laser from pointcloud_to_laserscan produces a scan line that does not register to the cloud2 in rviz .

image description

image description

image description

from rostopic list

/camera_info
/clicked_point
/clock
/cmd_vel
/depth/image_raw
/depth/points
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/gmapping_node/entropy
/image_raw
/image_raw/compressed
/image_raw/compressed/parameter_descriptions
/image_raw/compressed/parameter_updates
/image_raw/compressedDepth
/image_raw/compressedDepth/parameter_descriptions
/image_raw/compressedDepth/parameter_updates
/image_raw/theora
/image_raw/theora/parameter_descriptions
/image_raw/theora/parameter_updates


 self.msgAry  = [self.createStaticTransform("base_footprint",  0,  0,  0.1,  "base_link", 0, 0, 0),   \
                 self.createStaticTransform("base_link",  -0.13,  -0.13,  0.1,  "left_wheel", 0, 0, 0),   \
                 self.createStaticTransform("base_link",  -0.13,  0.13,  0.1,  "right_wheel", 0, 0, 0),   \
                 self.createStaticTransform("base_link",  -0.1,  0,  0.1,  "tower_link", 0, 0, 0),   \
                 self.createStaticTransform("tower_link", 0.0,  0,  0.2,  "camera_link", 0, 0, 0),  \
                 self.createStaticTransform("camera_link", 0,  0,  0,  "camera_frame_optical", 0, 0, 0),  \
                 self.createStaticTransform("camera_link", 0, 0,  0,  "rrbot/camera_frame",  -1.57079633,  0,  -1.57079633)]  

 self.pub_tf.publish(self.msgAry)




  <!-- ******************************************************************************************** -->

  <node name="pointcloud_to_laserscan_node" pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node"  output="screen" respawn="true">
      <remap from="cloud_in" to="/depth/points"/>
      <rosparam>
            target_frame: "camera_frame_optical"
            tolerance: 0.01
            min_height: 1.0
            max_height: 10.0

            angle_min: -1.5708 # -M_PI/2
            angle_max: 1.5708 # M_PI/2
            angle_increment: 0.00436717644334
            scan_time: 0.3333
            range_min: 0.1
            range_max: 30.0
            use_inf: false

            # Concurrency level, affects number of pointclouds queued for processing and number of threads used
            # 0 : Detect number of cores
            # 1 : Single threaded
            # 2->inf : Parallelism level
            concurrency_level: 0
       </rosparam>
  </node>

eg: of scan output

header: 
  seq: 530
  stamp: 
    secs: 435
    nsecs: 155000000
  frame_id: rrbot/camera_frame
angle_min: -1.57079994678
angle_max: 1.57079994678
angle_increment: 0.00436717644334
time_increment: 0.0
scan_time: 0.333299994469
range_min: 0.10000000149
range_max: 30.0
ranges: [31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31.0, 31 ...
(more)
edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
1

answered 2015-03-21 18:59:25 -0600

paulbovbel gravatar image

This is probably due to you not providing pointcloud_to_laserscan with a target frame. Camera frames are differently oriented ( http://www.ros.org/reps/rep-0103.html... ). Pointcloud_to_laserscan projects the pointcloud onto the x-y plane, so if the camera frame is used, the laserscan will end up 'vertical'.

edit flag offensive delete link more

Comments

The point cloud comes from the depth points from the gazebo kentic plugin which is converted to a scan line with a target frame of rrbot/camera_frame which is the same frame the riviz point cloud2 is using to display the voxel image. You can see both in the images.

rnunziata gravatar image rnunziata  ( 2015-03-22 11:28:12 -0600 )edit

Yes, and the camera_frame is oriented differently than you may expect (z-forward, x-right, y-up). pointcloud_to_laserscan will try to output a laserscan on the x-y plane, which is why it's 'upright'. Use a body-oriented frame (x-forward, y-left, z-up) such as 'base_link' as the target frame.

paulbovbel gravatar image paulbovbel  ( 2015-03-22 11:39:04 -0600 )edit

OK...tried to reset the target frame in PtoS and get this error which I do not understand

Can't transform pointcloud from frame rrbot/camera_frame to camera_frame_optical  with tolerance 0.01
rnunziata gravatar image rnunziata  ( 2015-03-22 15:18:35 -0600 )edit

https://github.com/ros-perception/per...

This means there's a problem with your transform tree. Post the results of rqt_graph.

paulbovbel gravatar image paulbovbel  ( 2015-03-22 15:25:03 -0600 )edit

If you have a camera_frame and camera_frame_optical, then camera_frame should hypothetically be fine to use as a target_frame. You want to avoid using frames that use the _optical convention.

paulbovbel gravatar image paulbovbel  ( 2015-03-22 15:26:05 -0600 )edit

I have updated the problem statement to include additional data.

rnunziata gravatar image rnunziata  ( 2015-03-22 16:12:42 -0600 )edit

Looks like you have a weird prefixing thing going on. Your pointclouds are coming in with frame "rrbot/camera_frame", but your tf tree contains "rrbot_camera_frame"

paulbovbel gravatar image paulbovbel  ( 2015-03-22 16:56:32 -0600 )edit

I saw that but assumed it was how it handled the display was not an issue. I does find the frame and processes it with rotation on the static transform which is displayed correctly in rviz.

rnunziata gravatar image rnunziata  ( 2015-03-22 17:27:57 -0600 )edit
0

answered 2015-06-08 03:22:49 -0600

Kushaagra gravatar image

I am also getting a similar problem with the following message. Can't transform pointcloud from frame camera_depth_frame_optical to camera_depth_frame with tolerance 0.01. Could someone guide how to solve this issue.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2015-03-21 13:10:41 -0600

Seen: 1,025 times

Last updated: Mar 23 '15