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

Configuration of pointcloud_to_laserscan with stereo camera. [closed]

asked 2015-03-13 06:54:01 -0500

Tanmay gravatar image

updated 2015-03-13 07:09:35 -0500

Hello,

I am trying to generate a laserscan of my environment by converting a pointcloud generated by a stereo camera, using the pointcloud_to_laserscan package, and I'm facing some issues. The details -

I am running the minoru stereo camera to generate the pointcloud, using uvc_camera's stereo node. (stereo_node.launch in uvc_camera/launch). I'm able to successfully access and manipulate the pointcloud received (/points as well as /points2). I also remapped the point cloud to /cloud_in, as required by pointcloud_to_laserscan.

To use pointcloud_to_laserscan, installed it (apt-get install, pre-built installation), on ROS Hydro. I modified the sample_node.launch file to my own launch file, minoru_laser.launch -

<launch>
<arg name="camera" default="camera" />
<!-- run pointcloud_to_laserscan node -->
<node pkg="pointcloud_to_laserscan" type="pointcloud_to_laserscan_node" name="pointcloud_to_laserscan">
    <param name="use_inf" value="false"/>
    <param name="use_concurrency" value="true"/>
    <!-- <param name="target_frame" value="camera"/> -->
    <!-- <remap from="cloud_in" to="$(arg camera)/depth_registered/points_processed"/> -->
    <!-- <remap from="scan" to="$(arg camera)/scan"/> -->
</node>

</launch>

Since I'm using a stereo camera, I have removed the OpenNI device node that was previously called, and I am not running the remaps.

I am also running a few nodes from navigation stack robot setup - tf_broadcaster -giving me the transformation between the base_link and camera frames. The camera frame is the default frame of the camera feeds as well as the input point cloud.

The issues I'm facing are as follows -

1) While the pointcloud itself is fine, when I echo the /scan, it has ONLY INF values (when use_inf is set to true), and = range_max + 1 (when use_inf is false). This occurs irrespective of what the pointcloud contains, whether it is within the maximum range or not.

2) Now given the range_max + 1 pointcloud, I should still be able to view this in RVIZ, which I am unable to do. The screen is just blank.

Some other details: I think it is a transformation frame issue, between the camera frame and the frame of the laser, but I am unable to figure out how to solve this. I ran rqt_console and changed the logger level of pointcloud_to_laserscan to debug, and saw this message -

    Node: /pointcloud_to_laserscan
    Time: 17:17:52.694141586 (2015-03-13) Severity: Debug 
Published Topics: /rosout, /scan

Connection::drop(2)

Location:
/tmp/buildd/ros-hydro-roscpp-1.10.2-0precise-20140304-0105/src/libros/connection.cpp:Connection::drop:324

As well as :

Node: /pointcloud_to_laserscan
Time: 17:17:52.694023811 (2015-03-13)
Severity: Debug
Published Topics: /rosout, /scan

TCP socket [9] closed

Location:
/tmp/buildd/ros-hydro-roscpp-1.10.2-0precise-20140304-0105/src/libros/transport/transport_tcp.cpp:TransportTCP::close:421

----------------------------------------------------------------------------------------------------

My rqt_graph is here. image description

Can anyone suggest a method to solve this?

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Tanmay
close date 2015-03-15 04:11:12.957103

2 Answers

Sort by ยป oldest newest most voted
0

answered 2015-03-15 04:10:09 -0500

Tanmay gravatar image

I managed to sort out the error.

Thanks to Paul's input, I found that ALL the points from the input cloud were being rejected, for various reasons. The common cause for each of them being rejected was that there is a difference between camera frames as provided by most ROS camera drivers (uvc_driver in my case), and how a laserscan frame is defined.

Camera frames have their z axis perpendicular to the image plane, x towards right, and y downwards along the image plane. Laser scan frames require x axis being along the forward direction (equivalent to z of camera frames), z upwards and y to the left.

I set up a transformation node between the initial camera frame and a base_link frame, with quaternions configured for the above frame mapping, enabled the target frame in the pointcloud_to_laserscan launch file, and the problem was solved.

edit flag offensive delete link more

Comments

I seem to have the same problem. Did you mean that you had added <param name="target_frame" value="base_link"> to your launch file and the problem went away?

cvcook gravatar image cvcook  ( 2015-07-14 18:00:44 -0500 )edit

I think I added a transformation broadcaster to rotate the frames accordingly. That's a 90 degree rotation about the y axis and then about the x axis, depending on how you look at it. The translation was just 0, 0, 0.

Tanmay gravatar image Tanmay  ( 2015-07-14 19:05:17 -0500 )edit
1

answered 2015-03-14 12:45:22 -0500

paulbovbel gravatar image

If you're getting inf. values, but cannot figure out why, clone and compile pointcloud_to_laserscan from source, and turn on debug messages. You should be able to see messages such as this, which will tell you why the points are being rejected.

edit flag offensive delete link more

Comments

Thanks for the input. I had done the same, and I was getting more than one of the errors - mostly that the points were being rejected for nan values (although some were out of the height range).

Tanmay gravatar image Tanmay  ( 2015-03-15 04:05:32 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2015-03-13 06:54:01 -0500

Seen: 1,566 times

Last updated: Mar 15 '15