stereodcam
Stereodcam is the node used to retrieve images from the videre stereo camera as part of the new image processing pipeline. Stereodcam retrieves messages from the camera and makes them available as a single raw_stereo message. Stereoproc then converts these raw_stereo messages into corresponding left, right, and disparity images. This allows us to log raw_disparity messages to a bag file and then replay them through different stereo processing algorithms.
Relevant Message Types
Stereodcam makes use of the messages in "sensor_msgs"
Image.msg: defines an image. This can be easily converted to an IPL image through the use of the CvBridge.
CamInfo.msg: defines camera intrinsic and extrinsic parameters associated with an image
StereoInfo.msg: defines camera parameters relevant to the computation of stereo.
DisparityInfo.msg: defines disparity parameters that were used in computing disparity
RawStereo.msg: defines the information as it comes directly out of the camera with minimal processing. This is made up of 2 Images, and a StereoInfo message.
Relevant Nodes
stereodcam
stereodcam is located in the dcam package. It connects to the videre and publishes raw_stereo messages.
stereoproc
stereoproc is located in the stereo_image_proc package. It listens to raw_stereo messages and converts them to a usable format, including image rectification, colorization, and stereo processing.
stereo_view
stereo_view is located in the stereo_view package. It is a simple viewer and demonstrates appropriate usage of CvBridge and the TopicSynchronizer.
Important Namespaces
stereoproc listens on the topic raw_stereo, and stereodcam publishes raw_stereo. Thus, both nodes must be in the same namespace for them to communicate with eachother. Generally, we'll want both nodes to be in the stereo namespace, but this may change once we have multiple sets of stereocameras on the robot. Each node is configured using private parameters (thus residing in /stereo/stereodcam/ or /stereo/stereoproc/ namespaces).
Parameters
stereodcam
- stereo/videre_mode (string)
- none = both images unrectified. This is mode supports retrieving color images from the camera.
- rectified = both images are rectified. Due to on-board rectification, color images cannot be retrieved in this mode.
- disparity = left image rectified + disparity. This mode does not support color and does not provide a right image.
- disparity_raw = left image unrectified + disparity. This mode supports color, but does not provide a right image.
- exposure (int)
- brightness (int)
- gain (int)
- fps (double) = frames per second. Defaults to the maximum the camera can provide.
stereoproc
- do_colorize = whether or not software color processing should be performed by stereoproc
- do_rectify = whether or not software rectification should be performed by stereoproc
- do_stereo = whether or not software stereo should be performed by stereoproc
- do_calc_points = whether or not stereoproc should generate a pointcloud
- do_keep_coords = whether or not to preserve the image x,y in the computed pointcloud
Running
First make sure that you have build stereodcam. It is part of the dcam package.
rosmake dcam
The following roslaunch file will start up the stereodcam node and stereoproc node:
<launch> <group ns="stereo"> <node machine="stereo" pkg="dcam" type="stereodcam" respawn="false" name="stereodcam"> <param name="videre_mode" type="str" value="none"/> </node> <node machine="stereo" pkg="stereo_image_proc" type="stereoproc" respawn="false" output="screen" name="stereoproc"> <param name="do_rectify" type="bool" value="true"/> <param name="do_stereo" type="bool" value="True"/> <param name="do_calc_points" type="bool" value="True"/> <param name="do_keep_coords" type="bool" value="True"/> </node> </group> </launch>
Note that due to a bug in roslaunch Ticket #1300, both nodes need the name attribute set in order for the private boolean params to be set. Otherwise, the params will take their default values, and you'll probably get unexpected results (like a black image because the exposure is too short).
A slightly longer version can be found in the file videre.launch in the package dcam which also shows how to set exposure, brightness, and gain.
Once this script has been launched:
ssh prg4 % connect to the node on the machine with the firewire interface roscd dcam roslaunch videre.launch
You can view it using the stereo_view node: rosrun stereo_view stereo_view
You can change some of the parameters, such as exposure, brightness and gain, online using rosparam set <parameter> <value>, and then running dcam/bin/check_params. For example:
rosparam set stereo/stereodcam/exposure 450 roscd dcam ./bin/check_params
(on the videre cameras, exposure ranges between 0-529, corresponding to a number of rows in the image.) Note that if the exposure, gain, etc. are set to "auto", the videre cameras cannot return their actual value.
Recording
When recording it is best practice to simply record the raw_stereo message such as:
rosbag record -O bags/myviderebag stereo/raw_stereo
Note: when playing back, you will need to have the stereoproc node running
stereodcam
Stereodcam is the node used to retrieve images from the videre stereo camera as part of the new image processing pipeline. Stereodcam retrieves messages from the camera and makes them available as a single raw_stereo message. Stereoproc then converts these raw_stereo messages into corresponding left, right, and disparity images. This allows us to log raw_disparity messages to a bag file and then replay them through different stereo processing algorithms.
Relevant Message Types
Stereodcam makes use of the messages in "sensor_msgs"
Image.msg: defines an image. This can be easily converted to an IPL image through the use of the CvBridge.
CamInfo.msg: defines camera intrinsic and extrinsic parameters associated with an image
StereoInfo.msg: defines camera parameters relevant to the computation of stereo.
DisparityInfo.msg: defines disparity parameters that were used in computing disparity
RawStereo.msg: defines the information as it comes directly out of the camera with minimal processing. This is made up of 2 Images, and a StereoInfo message.
Relevant Nodes
stereodcam
stereodcam is located in the dcam package. It connects to the videre and publishes raw_stereo messages.
stereoproc
stereoproc is located in the stereo_image_proc package. It listens to raw_stereo messages and converts them to a usable format, including image rectification, colorization, and stereo processing.
stereo_view
stereo_view is located in the stereo_view package. It is a simple viewer and demonstrates appropriate usage of CvBridge and the TopicSynchronizer.
Important Namespaces
stereoproc listens on the topic raw_stereo, and stereodcam publishes raw_stereo. Thus, both nodes must be in the same namespace for them to communicate with eachother. Generally, we'll want both nodes to be in the stereo namespace, but this may change once we have multiple sets of stereocameras on the robot. Each node is configured using private parameters (thus residing in /stereo/stereodcam/ or /stereo/stereoproc/ namespaces).
Parameters
stereodcam
- stereo/videre_mode (string)
- none = both images unrectified. This is mode supports retrieving color images from the camera.
- rectified = both images are rectified. Due to on-board rectification, color images cannot be retrieved in this mode.
- disparity = left image rectified + disparity. This mode does not support color and does not provide a right image.
- disparity_raw = left image unrectified + disparity. This mode supports color, but does not provide a right image.
- exposure (int)
- brightness (int)
- gain (int)
- fps (double) = frames per second. Defaults to the maximum the camera can provide.
stereoproc
- do_colorize = whether or not software color processing should be performed by stereoproc
- do_rectify = whether or not software rectification should be performed by stereoproc
- do_stereo = whether or not software stereo should be performed by stereoproc
- do_calc_points = whether or not stereoproc should generate a pointcloud
- do_keep_coords = whether or not to preserve the image x,y in the computed pointcloud
Running
First make sure that you have build stereodcam. It is part of the dcam package.
rosmake dcam
The following roslaunch file will start up the stereodcam node and stereoproc node:
<launch> <group ns="stereo"> <node machine="stereo" pkg="dcam" type="stereodcam" respawn="false" name="stereodcam"> <param name="videre_mode" type="str" value="none"/> </node> <node machine="stereo" pkg="stereo_image_proc" type="stereoproc" respawn="false" output="screen" name="stereoproc"> <param name="do_rectify" type="bool" value="true"/> <param name="do_stereo" type="bool" value="True"/> <param name="do_calc_points" type="bool" value="True"/> <param name="do_keep_coords" type="bool" value="True"/> </node> </group> </launch>
Note that due to a bug in roslaunch Ticket #1300, both nodes need the name attribute set in order for the private boolean params to be set. Otherwise, the params will take their default values, and you'll probably get unexpected results (like a black image because the exposure is too short).
A slightly longer version can be found in the file videre.launch in the package dcam which also shows how to set exposure, brightness, and gain.
Once this script has been launched:
ssh prg4 % connect to the node on the machine with the firewire interface roscd dcam roslaunch videre.launch
You can view it using the stereo_view node: rosrun stereo_view stereo_view
You can change some of the parameters, such as exposure, brightness and gain, online using rosparam set <parameter> <value>, and then running dcam/bin/check_params. For example:
rosparam set stereo/stereodcam/exposure 450 roscd dcam ./bin/check_params
(on the videre cameras, exposure ranges between 0-529, corresponding to a number of rows in the image.) Note that if the exposure, gain, etc. are set to "auto", the videre cameras cannot return their actual value.
Recording
When recording it is best practice to simply record the raw_stereo message such as:
rosrecord -f bags/myviderebag stereo/raw_stereo
Note: when playing back, you will need to have the stereoproc node running