This script calls the RequestData action of the stereo camera to get the latest point cloud. It also calls the RequestDataMono to get the latest rectified (undistorted) image from the mono camera node. In the end it calls the TexturedPointCloud to project the point cloud of the stereo camera into the mono camera's camera_frame. In the end the pixel values of the mono camera's image are applied to the projected point cloud.

Note: In Order to use this script, the stereo and mono camera nodes have to be used as nodelets. This is essential, because there are commands used internally, which need to run within the same NxLib instance. In addition, the mono camera needs also a link to the stereo camera. The steps are described here.

Parameters

~timeout (double, default: 60)

  • A timeout in seconds for waiting for the cameras to become available.
~rate (double, default: 2)
  • Defines the publishing rate of the script.
~rgb_serial (string)
  • The serial of the mono camera.
~stereo_ns (string, default: "/stereo_camera")
  • The namespace of the stereo camera, in which its actions/topics are scoped.
~rgb_ns (string, default: "/rgb_camera")
  • The namespace of the mono camera, in which its actions/topics are scoped.

Published Topics

In this script the actions RequestDataMono for mono cameras and RequestData for stereo cameras are called. Their topics will be published in their namespaces respectively. The called TexturedPointCloud action will also publish the colored point cloud message like the following:

/<stereo_ns>/point_cloud_color (sensor_msgs/PointCloud2)

  • The colored point cloud.

Wiki: ensenso_driver/Nodes/color_point_cloud (last edited 2019-08-07 14:30:11 by YasinGuenduez)