Skip to content

Commit

Permalink
Merge pull request #14 from reaganlo/release-1.0.1
Browse files Browse the repository at this point in the history
Release 1.0.1
  • Loading branch information
reaganlo committed Mar 18, 2016
2 parents bb1874d + 5a22ca4 commit 199e42c
Show file tree
Hide file tree
Showing 17 changed files with 872 additions and 459 deletions.
49 changes: 43 additions & 6 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -1,15 +1,52 @@
# git ls-files --others --exclude-from=.git/info/exclude
# Lines that start with '#' are comments.
# See http://git-scm.com/docs/gitignore

# Don't check in Top Level CMakeLists.txt
/CMakeLists.txt
build/
bin/
lib/
msg_gen/
srv_gen/
msg/*Action.msg
msg/*ActionFeedback.msg
msg/*ActionGoal.msg
msg/*ActionResult.msg
msg/*Feedback.msg
msg/*Goal.msg
msg/*Result.msg
msg/_*.py

# Ignore all Linux Editor revision save files
*~
# Generated by dynamic reconfigure
*.cfgc
/cfg/cpp/
/cfg/*.py

# Ignore generated docs
*.dox
*.wikidoc

# Ignore all hidden files
# eclipse stuff
.project
.cproject
.settings

# qcreator stuff
CMakeLists.txt.user

srv/_*.py
*.pcd
*.pyc
qtcreator-*
*.user

/planning/cfg
/planning/docs
/planning/src

# Ignore all Linux Editor revision save files
*~

# Emacs
.#*

# Catkin custom files
CATKIN_IGNORE
24 changes: 24 additions & 0 deletions camera/CHANGELOG.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package realsense_camera
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

1.0.1 (2016-03-17)
------------------
* Convert command line args to ROS params
This also fixes Issue #9 for publish_tf and enable_tf
Updated README to indicate changes in R200_DISPARITY_MULTIPLIER.
* New Feature to dynamically enable/disable depth stream
Note: Enable/disable of depth stream also enables/disables infrared streams.
* Update camera_info msgs
Add identity matrix for rotation
Add depth to color translation to projection matrix
* Add rgbd_launch as run dependency.
* Add missing Change Log history file
This is a required file as part of the ROS (bloom) release process
which was missed from our initial release.
* Contributors: Mark D Horn, Matthew Hansen, Reagan Lopez, Rajvi Jingar

1.0.0 (2016-02-29)
------------------
* Initial Release
* Contributors: Rajvi Jingar, Reagan Lopez
91 changes: 46 additions & 45 deletions camera/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -72,33 +72,32 @@ Infrared2 camera

#### Static Parameters

mode (string, default: preset)
Specify the mode to start camera streams. Mode comprises of height, width and fps.
Preset mode enables default values whereas Manual mode enables the specified parameter values.
color_height (int, default: 480)
Specify the color camera height resolution.
color_width (int, default: 640)
Specify the color camera width resolution.
depth_height (int, default: 360)
Specify the depth camera height resolution.
depth_width (int, default: 480)
Specify the depth camera width resolution.
depth_fps (int, default: 60)
Specify the color camera FPS
depth_fps (int, default: 60)
Specify the depth camera FPS
enable_depth (bool, default: true)
Specify if to enable or not the depth camera.
enable_color (bool, default: true)
Specify if to enable or not the color camera.
enable_pointcloud (bool, default: true)
Specify if to enable or not the point cloud camera.
enable_tf (bool, default: true)
Specify if to enable or not the transform frames.
camera (string, default: "R200")
Specify the camera name.
Supported options: Following are the options supported by the R200 camera:
R200_DEPTH_CONTROL_PRESET : [0, 5]
Stream parameters:
mode (string, default: preset)
Specify the mode to start camera streams. Mode comprises of height, width and fps.
Preset mode enables default values whereas Manual mode enables the specified parameter values.
color_height (int, default: 480)
Specify the color camera height resolution.
color_width (int, default: 640)
Specify the color camera width resolution.
depth_height (int, default: 360)
Specify the depth camera height resolution.
depth_width (int, default: 480)
Specify the depth camera width resolution.
depth_fps (int, default: 60)
Specify the color camera FPS
depth_fps (int, default: 60)
Specify the depth camera FPS
enable_color (bool, default: true)
Specify if to enable or not the color camera.
enable_pointcloud (bool, default: true)
Specify if to enable or not the point cloud camera.
enable_tf (bool, default: true)
Specify if to enable or not the transform frames.
camera (string, default: "R200")
Specify the camera name.
Camera parameters:
Following are the parameters that can be set only statically in the R200 camera:
R200_DEPTH_UNITS : [1, 2147483647]
R200_DEPTH_CLAMP_MIN : [0, 65535]
R200_DEPTH_CLAMP_MAX : [0, 65535]
Expand All @@ -119,8 +118,14 @@ Infrared2 camera
To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon.

####Dynamic Parameters
List of dynamically configurable camera options:

Stream parameters:
enable_depth (bool, default: true)
Specify if to enable or not the depth and infrared camera.
Note: Infrared streams will be enabled or disabled along with depth stream.

Camera parameters:
Following are the parameters that can be set dynamically as well as statically in the R200 camera.
COLOR_BACKLIGHT_COMPENSATION
COLOR_BRIGHTNESS
COLOR_CONTRAST
Expand All @@ -129,36 +134,32 @@ To get supported camera options with current value set. It returns string in opt
COLOR_HUE
COLOR_SATURATION
COLOR_SHARPNESS
COLOR_WHITE_BALANCE
COLOR_ENABLE_AUTO_WHITE_BALANCE
R200_LR_AUTO_EXPOSURE_ENABLED
COLOR_WHITE_BALANCE (Must be set only if COLOR_ENABLE_AUTO_WHITE_BALANCE is disabled)
R200_LR_GAIN
R200_LR_EXPOSURE
R200_EMITTER_ENABLED
R200_DISPARITY_MULTIPLIER
R200_AUTO_EXPOSURE_TOP_EDGE
R200_AUTO_EXPOSURE_BOTTOM_EDGE
R200_AUTO_EXPOSURE_LEFT_EDGE
R200_AUTO_EXPOSURE_RIGHT_EDGE
R200_DISPARITY_MULTIPLIER (This parameter does not work in the latest R200 firmware release. Likely to be removed in the next ros-realsense release.)
R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled)
Following are the parameters that can only be set dynamically in the R200 camera.
R200_LR_AUTO_EXPOSURE_ENABLED
R200_AUTO_EXPOSURE_TOP_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled)
R200_AUTO_EXPOSURE_BOTTOM_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled)
R200_AUTO_EXPOSURE_LEFT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled)
R200_AUTO_EXPOSURE_RIGHT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled)

Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure.
Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image.
E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239)

Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure.
Command to launch GUI:

$ rosrun rqt_reconfigure rqt_reconfigure

Change options commandline using following command:
Command to change dynamic parameters using commandline:

$ rosrun dynamic_reconfigure dynparam set /<node> <parameter_name> <value>
E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2

Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image.
E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239)

To change EDGE parameters, R200_LR_AUTO_EXPOSURE_ENABLED should be enabled.
To set R200_LR_EXPOSURE, R200_LR_AUTO_EXPOSURE_ENABLED should be disabled.
To set COLOR_WHITE_BALANCE, COLOR_ENABLE_AUTO_WHITE_BALANCE should be disabled.


###Running the R200 nodelet

Expand Down
41 changes: 21 additions & 20 deletions camera/cfg/camera_params.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -6,25 +6,26 @@ from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

# Name Type Level Description Default Min Max
gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4)
gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255)
gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64)
gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256)
gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280)
gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200)
gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255)
gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7)
gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000)
gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1)
gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1)
gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399)
gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164)
gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1)
gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000)
gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479)
gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479)
gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639)
gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639)
# Name Type Level Description Default Min Max
gen.add("enable_depth", bool_t, 0, "Enable Depth", True)
gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4)
gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255)
gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64)
gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256)
gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280)
gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200)
gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255)
gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7)
gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000)
gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1)
gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1)
gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399)
gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164)
gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1)
gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000)
gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479)
gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479)
gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639)
gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639)

exit(gen.generate(PACKAGE, "realsense_camera", "camera_params"))
25 changes: 11 additions & 14 deletions camera/launch/includes/realsense_r200_nodelet.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,37 +4,34 @@

<arg name="depth_frame_id" default="camera_depth_optical_frame" />
<arg name="rgb_frame_id" default="camera_rgb_optical_frame" />
<arg name="publish_tf" default="false" />
<arg name="publish_tf" default="true" />
<arg name="depth" default="depth" />
<arg name="rgb" default="rgb" />
<arg name="ir" default="ir" />
<arg name="ir2" default="ir2" />
<arg name="mode" default="preset" />
<arg name="enable_depth" default="true" />
<arg name="enable_color" default="true" />
<arg name="enable_ir" default="true" />

<!-- "enable_depth_ir" will take the value of "enable_ir" only if "enable_ir" is true.
Else "enable_depth_ir" will take the value of "enable_depth" -->
<arg name="enable_depth_ir" value="$(arg enable_ir)" if="$(arg enable_ir)" />
<arg name="enable_depth_ir" value="$(arg enable_depth)" unless="$(arg enable_ir)" />

<!-- "enable_tf" will be set to false only if "publish_tf" is true. Else it is set to true.
Ensures that the nodelet does not publish tf if the transforms are published statically. -->
<arg name="enable_tf" value="false" if="$(arg publish_tf)" />
<arg name="enable_tf" value="true" unless="$(arg publish_tf)" />
<arg name="enable_depth_ir" value="$(arg enable_depth)" unless="$(arg enable_ir)" />

<!-- "enable_pointcloud" is set to false by default because rgbd launch uses standard ROS packages
to generate point clouds. -->
<arg name="enable_pointcloud" default="false" />

<node pkg="nodelet" type="nodelet" name="camera_nodelet"
args="load realsense_camera/RealsenseNodelet $(arg manager)
depth_frame_id $(arg depth_frame_id)
rgb_frame_id $(arg rgb_frame_id)
enable_depth $(arg enable_depth_ir)
enable_color $(arg enable_color)
enable_pointcloud $(arg enable_pointcloud)
enable_tf $(arg enable_tf)">
args="load realsense_camera/RealsenseNodelet $(arg manager)">
<param name="mode" type="str" value="$(arg mode)" />
<param name="enable_depth" type="bool" value="$(arg enable_depth_ir)" />
<param name="enable_color" type="bool" value="$(arg enable_color)" />
<param name="enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="enable_tf" type="bool" value="$(arg publish_tf)" />
<param name="depth_frame_id" type="str" value="$(arg depth_frame_id)" />
<param name="rgb_frame_id" type="str" value="$(arg rgb_frame_id)" />

<remap from="camera/depth/image_raw" to="$(arg depth)/image_raw" />
<remap from="camera/color/image_raw" to="$(arg rgb)/image_raw" />
Expand Down
18 changes: 9 additions & 9 deletions camera/launch/realsense_r200_navigation.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@

<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>

<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet
mode $(arg mode)
enable_depth $(arg enable_depth)
enable_color $(arg enable_color)
enable_pointcloud $(arg enable_pointcloud)
enable_tf $(arg enable_tf)">
</node>
<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet" >
<param name="mode" type="str" value="$(arg mode)" />
<param name="enable_depth" type="bool" value="$(arg enable_depth)" />
<param name="enable_color" type="bool" value="$(arg enable_color)" />
<param name="enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="enable_tf" type="bool" value="$(arg enable_tf)" />
</node>

</launch>
29 changes: 15 additions & 14 deletions camera/launch/realsense_r200_nodelet_standalone_manual.launch
Original file line number Diff line number Diff line change
Expand Up @@ -14,18 +14,19 @@

<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>

<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet
mode $(arg mode)
color_height $(arg color_height)
color_width $(arg color_width)
depth_height $(arg depth_height)
depth_width $(arg depth_width)
enable_color $(arg enable_color)
enable_depth $(arg enable_depth)
depth_fps $(arg depth_fps)
color_fps $(arg color_fps)
enable_pointcloud $(arg enable_pointcloud)">
</node>

<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet">
<param name="mode" type="str" value="$(arg mode)" />
<param name="enable_depth" type="bool" value="$(arg enable_depth)" />
<param name="enable_color" type="bool" value="$(arg enable_color)" />
<param name="enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="enable_tf" type="bool" value="$(arg enable_tf)" />
<param name="depth_width" type="int" value="$(arg depth_width)" />
<param name="depth_height" type="int" value="$(arg depth_height)" />
<param name="color_width" type="int" value="$(arg color_width)" />
<param name="color_height" type="int" value="$(arg color_height)" />
<param name="depth_fps" type="int" value="$(arg depth_fps)" />
<param name="color_fps" type="int" value="$(arg color_fps)" />
</node>

</launch>
18 changes: 9 additions & 9 deletions camera/launch/realsense_r200_nodelet_standalone_preset.launch
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@

<node pkg="nodelet" type="nodelet" name="standalone_nodelet" args="manager" output="screen"/>

<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet
mode $(arg mode)
enable_depth $(arg enable_depth)
enable_color $(arg enable_color)
enable_pointcloud $(arg enable_pointcloud)
enable_tf $(arg enable_tf)">
</node>
<node pkg="nodelet" type="nodelet" name="RealsenseNodelet"
args="load realsense_camera/RealsenseNodelet standalone_nodelet">
<param name="mode" type="str" value="$(arg mode)" />
<param name="enable_depth" type="bool" value="$(arg enable_depth)" />
<param name="enable_color" type="bool" value="$(arg enable_color)" />
<param name="enable_pointcloud" type="bool" value="$(arg enable_pointcloud)" />
<param name="enable_tf" type="bool" value="$(arg enable_tf)" />
</node>

</launch>
Loading

0 comments on commit 199e42c

Please sign in to comment.