(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Changing Camera Parameters from the Default Presets

Description: This tutorial explains how to change from the default camera parameters to customer configurations for items such as width, height, frames per second, etc.

Keywords: realsense, custom

Tutorial Level: INTERMEDIATE

Copy the example modification launch file

roscp realsense_camera r200_nodelet_modify_params.launch my_custom_realsense.launch

Example content of r200_nodelet_modify_params.launch

   1 <!-- Sample launch file for modifying the parameters of RealSense R200 camera -->
   2 <launch>
   3   <arg name="manager"      value="nodelet_manager" />
   4   <arg name="camera"       default="camera" />
   5   <arg name="camera_type"  default="R200" /> <!-- Type of camera -->
   6   <arg name="serial_no"    default="" />
   7   <arg name="usb_port_id"  default="" /> <!-- USB "Bus#-PortPath#" -->
   8 
   9   <!-- These 'arg' tags are just place-holders for passing values from test files.
  10   The recommended way is to pass the values directly into the 'param' tags. -->
  11   <arg name="enable_depth"      default="true" />
  12   <arg name="enable_color"      default="true" />
  13   <arg name="enable_tf"         default="true" />
  14   <arg name="mode"              default="manual" />
  15   <arg name="depth_width"       default="640" />
  16   <arg name="depth_height"      default="480" />
  17   <arg name="color_width"       default="1920" />
  18   <arg name="color_height"      default="1080" />
  19   <arg name="depth_fps"         default="30" />
  20   <arg name="color_fps"         default="30" />
  21 
  22   <param name="$(arg camera)/driver/enable_depth"      type="bool" value="$(arg enable_depth)" />
  23   <param name="$(arg camera)/driver/enable_color"      type="bool" value="$(arg enable_color)" />
  24   <param name="$(arg camera)/driver/enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
  25   <param name="$(arg camera)/driver/enable_tf"         type="bool" value="$(arg enable_tf)" />
  26   <param name="$(arg camera)/driver/mode"              type="str"  value="$(arg mode)" />
  27   <param name="$(arg camera)/driver/depth_width"       type="int"  value="$(arg depth_width)" />
  28   <param name="$(arg camera)/driver/depth_height"      type="int"  value="$(arg depth_height)" />
  29   <param name="$(arg camera)/driver/color_width"       type="int"  value="$(arg color_width)" />
  30   <param name="$(arg camera)/driver/color_height"      type="int"  value="$(arg color_height)" />
  31   <param name="$(arg camera)/driver/depth_fps"         type="int"  value="$(arg depth_fps)" />
  32   <param name="$(arg camera)/driver/color_fps"         type="int"  value="$(arg color_fps)" />
  33   <!-- Refer to http://wiki.ros.org/realsense_camera for list of supported parameters -->
  34 
  35   <group ns="$(arg camera)">
  36     <node pkg="nodelet" type="nodelet" name="$(arg manager)" args="manager" output="screen"/>
  37 
  38     <include file="$(find realsense_camera)/launch/includes/nodelet.launch.xml">
  39       <arg name="manager"      value="$(arg manager)" />
  40       <arg name="camera"       value="$(arg camera)" />
  41       <arg name="camera_type"  value="$(arg camera_type)" />
  42       <arg name="serial_no"    value="$(arg serial_no)" />
  43       <arg name="usb_port_id"  value="$(arg usb_port_id)" />
  44     </include>
  45   </group>
  46 </launch>

Make Custom Updates

# Use your favorite editor to make changes
$EDITOR my_custom_realsense.launch

Set Camera Type

On line 5, set the camera_type to the appropriate value: R200, F200, SR300, ZR300, etc.

Set Camera Mode to Manual

If you want to change the the stream width, height, or frame rate, the camera mode must be set to manual on line 14. This will override the preset mode of 'best quality' and allow the individual <stream>_<option> to be set.

Set the Stream Values

The possible valid stream resolutions and frames per second for each supported camera are documented on the librealsense GitHub site.

Example of setting SR300 to 640x480@10fps

  • On line 5, set the camera_type to SR300.

  • On line 14, set the mode to manual.

  • On line 15, set the depth_width to the 640.

  • On line 16, set the depth_height  to the 480.

  • On line 17, set the color_width to the 640.

  • On line 18, set the color_height  to the 480.

  • On line 19, set the depth_fps to the 10.

  • On line 20, set the color_fps  to the 10.

Wiki: realsense_camera/Tutorials/change_camera_parameters (last edited 2016-11-17 03:24:38 by mdhorn)