|
From: <rdi...@us...> - 2009-01-06 10:55:02
|
Revision: 8878
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8878&view=rev
Author: rdiankov
Date: 2009-01-06 10:54:58 +0000 (Tue, 06 Jan 2009)
Log Message:
-----------
updated prf with new cameras, added checkerboard detection launch file
Modified Paths:
--------------
pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml
pkg/trunk/robot_descriptions/pr2_alpha/prf.launch
pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/control_laser_tilt_roslaunch.xml
Added Paths:
-----------
pkg/trunk/calibration/laser_camera_calibration/startcalib.ros.xml
Added: pkg/trunk/calibration/laser_camera_calibration/startcalib.ros.xml
===================================================================
--- pkg/trunk/calibration/laser_camera_calibration/startcalib.ros.xml (rev 0)
+++ pkg/trunk/calibration/laser_camera_calibration/startcalib.ros.xml 2009-01-06 10:54:58 UTC (rev 8878)
@@ -0,0 +1,24 @@
+<launch>
+ <machine name="localhost_cameras" address="localhost" default="false"/>
+
+<!-- <node machine="cameras" name="dcam" pkg="dcam" type="dcam" respawn="false">
+ <param name="video_mode" type="str" value="640x480_videre_rectified"/>
+ <param name="do_rectify" type="bool" value="False"/>
+ <param name="do_stereo" type="bool" value="False"/>
+ <param name="do_calc_points" type="bool" value="False"/>
+ </node> -->
+ <group ns="checkerdetector" clear_params="true">
+ <param name="display" type="int" value="1"/>
+ <param name="frame_id" type="string" value="head_tilt_link"/>
+ <param name="rect0_size_x" type="double" value="0.10740"/>
+ <param name="rect0_size_y" type="double" value="0.10757"/>
+ <param name="grid0_size_x" type="int" value="6"/>
+ <param name="grid0_size_y" type="int" value="8"/>
+ <param name="type0" type="string" value="data/ricebox.kinbody.xml"/>
+ <node machine="localhost_cameras" pkg="checkerboard_detector" type="checkerboard_detector" respawn="true" output="screen">
+ <remap from="CamInfo" to="/stereo/left/cam_info"/>
+ <remap from="Image" to="/stereo/left/image_rect"/>
+<!-- <env name="DISPLAY" value=":0.0"/> -->
+ </node>
+ </group>
+</launch>
Modified: pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml
===================================================================
--- pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml 2009-01-06 10:53:48 UTC (rev 8877)
+++ pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml 2009-01-06 10:54:58 UTC (rev 8878)
@@ -16,8 +16,8 @@
<param name="grid0_size_y" type="int" value="3"/>
<param name="type0" type="string" value="data/ricebox.kinbody.xml"/>
<node machine="localhost_cameras" pkg="checkerboard_detector" type="checkerboard_detector" respawn="true" output="screen">
- <remap from="CamInfo" to="/dcam/left/cam_info"/>
- <remap from="Image" to="/dcam/left/image_rect"/>
+ <remap from="CamInfo" to="/stereo/left/cam_info"/>
+ <remap from="Image" to="/stereo/left/image_rect"/>
<!-- <env name="DISPLAY" value=":0.0"/> -->
</node>
</group>
Modified: pkg/trunk/robot_descriptions/pr2_alpha/prf.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2_alpha/prf.launch 2009-01-06 10:53:48 UTC (rev 8877)
+++ pkg/trunk/robot_descriptions/pr2_alpha/prf.launch 2009-01-06 10:54:58 UTC (rev 8878)
@@ -63,8 +63,8 @@
-->
<!-- DCAM-->
-<node machine="three" name="dcam" pkg="dcam" type="dcam" respawn="false">
- <!-- video_mode should be one of the following:
+ <group ns="stereo">
+ <!-- video_mode should be one of the following:
640x480_videre_rectified: Provides rectified images from the hw
Provides: left mono image
640x480_videre_disparity: Disparity and rectification done on chip.
@@ -74,12 +74,16 @@
640x480_videre_none: No stereo on chip (all processing done in software).
Provides: all 3 images available
-->
- <param name="video_mode" type="str" value="640x480_videre_rectified"/>
- <param name="do_rectify" type="bool" value="False"/>
- <param name="do_stereo" type="bool" value="False"/>
- <param name="do_calc_points" type="bool" value="False"/>
-</node>
+ <param name="videre_mode" type="str" value="rectified"/>
+ <param name="do_colorize" type="bool" value="False"/>
+ <param name="do_rectify" type="bool" value="False"/>
+ <param name="do_stereo" type="bool" value="False"/>
+ <param name="do_calc_points" type="bool" value="False"/>
+ </group>
+ <node machine="three" pkg="dcam" type="stereodcam" respawn="false"/>
+ <node machine="three" pkg="stereo_image_proc" type="stereoproc" respawn="false"/>
+
<!-- Runtime Diagnostics Logging -->
<node pkg="rosrecord" type="rosrecord" args="-f /hwlog/prf_runtime_automatic /diagnostics" />
Modified: pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/control_laser_tilt_roslaunch.xml
===================================================================
--- pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/control_laser_tilt_roslaunch.xml 2009-01-06 10:53:48 UTC (rev 8877)
+++ pkg/trunk/robot_descriptions/wg_robot_description/laser_tilt/control_laser_tilt_roslaunch.xml 2009-01-06 10:54:58 UTC (rev 8878)
@@ -1,4 +1,4 @@
<launch>
- <node pkg="mechanism_control" type="spawner.py" args="laser_tilt_controller.xml" />
- <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 15 .75 .25" />
+ <node pkg="mechanism_control" type="spawner.py" args="$(find wg_robot_description)/laser_tilt/laser_tilt_controller.xml" />
+ <node pkg="pr2_mechanism_controllers" type="control_laser.py" args="laser_tilt_controller sine 10 .75 .25" />
</launch>
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|