|
From: <rdi...@us...> - 2008-12-27 09:40:43
|
Revision: 8612
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=8612&view=rev
Author: rdiankov
Date: 2008-12-27 09:40:39 +0000 (Sat, 27 Dec 2008)
Log Message:
-----------
added missing dependencies to pr2_alpha, fixed rosthread issue in robot_pose_ekf, checkerboard detector takes in tf frames
Modified Paths:
--------------
pkg/trunk/estimation/robot_pose_ekf/manifest.xml
pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml
pkg/trunk/robot_descriptions/pr2_alpha/manifest.xml
pkg/trunk/robot_descriptions/pr2_alpha/prf.launch
pkg/trunk/vision/checkerboard_detector/checkerboard_detector.cpp
Modified: pkg/trunk/estimation/robot_pose_ekf/manifest.xml
===================================================================
--- pkg/trunk/estimation/robot_pose_ekf/manifest.xml 2008-12-27 06:36:24 UTC (rev 8611)
+++ pkg/trunk/estimation/robot_pose_ekf/manifest.xml 2008-12-27 09:40:39 UTC (rev 8612)
@@ -7,4 +7,5 @@
<depend package="std_msgs" />
<depend package="robot_msgs" />
<depend package="tf" />
+<depend package="rosthread"/>
</package>
Modified: pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml
===================================================================
--- pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml 2008-12-27 06:36:24 UTC (rev 8611)
+++ pkg/trunk/openrave_planning/ormanipulation/startchecker.ros.xml 2008-12-27 09:40:39 UTC (rev 8612)
@@ -9,12 +9,13 @@
</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.02133"/>
<param name="rect0_size_y" type="double" value="0.021"/>
<param name="grid0_size_x" type="int" value="4"/>
<param name="grid0_size_y" type="int" value="3"/>
<param name="type0" type="string" value="data/ricebox.kinbody.xml"/>
- <node pkg="checkerboard_detector" type="checkerboard_detector" respawn="true" output="screen">
+ <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"/>
<!-- <env name="DISPLAY" value=":0.0"/> -->
Modified: pkg/trunk/robot_descriptions/pr2_alpha/manifest.xml
===================================================================
--- pkg/trunk/robot_descriptions/pr2_alpha/manifest.xml 2008-12-27 06:36:24 UTC (rev 8611)
+++ pkg/trunk/robot_descriptions/pr2_alpha/manifest.xml 2008-12-27 09:40:39 UTC (rev 8612)
@@ -19,6 +19,6 @@
<depend package="rosrecord"/>
<depend package="hokuyo_node"/>
<depend package="imu_node"/>
-
-
+ <depend package="dcam"/>
+ <depend package="robot_pose_ekf"/>
</package>
Modified: pkg/trunk/robot_descriptions/pr2_alpha/prf.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2_alpha/prf.launch 2008-12-27 06:36:24 UTC (rev 8611)
+++ pkg/trunk/robot_descriptions/pr2_alpha/prf.launch 2008-12-27 09:40:39 UTC (rev 8612)
@@ -63,14 +63,23 @@
-->
<!-- DCAM-->
-<!-- <node machine="three" name="dcam" pkg="dcam_node" type="dcam_node" respawn="false">
- <param name="video_mode" type="str" value="640x480_videre_none"/>
- <param name="do_rectify" type="bool" value="True"/>
- <param name="do_stereo" type="bool" value="True"/>
- <param name="do_calc_points" type="bool" value="False"/>
- </node> -->
+<node machine="three" name="dcam" pkg="dcam" type="dcam" respawn="false">
+ <!-- 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.
+ Provides: Disparity and left mono image
+ 640x480_videre_disparity_raw: Disparity done on chip (debayer and rectification in software).
+ Provides: disparity and left color image.
+ 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>
-
<!-- Runtime Diagnostics Logging -->
<node pkg="rosrecord" type="rosrecord" args="-f /hwlog/prf_runtime_automatic /diagnostics" />
Modified: pkg/trunk/vision/checkerboard_detector/checkerboard_detector.cpp
===================================================================
--- pkg/trunk/vision/checkerboard_detector/checkerboard_detector.cpp 2008-12-27 06:36:24 UTC (rev 8611)
+++ pkg/trunk/vision/checkerboard_detector/checkerboard_detector.cpp 2008-12-27 09:40:39 UTC (rev 8612)
@@ -58,6 +58,7 @@
image_msgs::Image _imagemsg;
checkerboard_detector::ObjectDetection _objdetmsg;
image_msgs::CvBridge _cvbridge;
+ string frame_id; // tf frame id
int display, uidnext;
vector<CHECKERBOARD> vcheckers; // grid points for every checkerboard
@@ -117,6 +118,8 @@
index++;
}
+ param("frame_id",frame_id,string(""));
+
if( maptypes.size() == 0 ) {
ROS_ERROR("no checkerboards to detect");
return;
@@ -245,6 +248,7 @@
}
_objdetmsg.set_objects_vec(vobjects);
+ _objdetmsg.header.frame_id = frame_id;
publish("ObjectDetection", _objdetmsg);
ROS_INFO("checkerboard: image: %dx%d (size=%d), num: %d, total: %.3fs",_caminfomsg.width,_caminfomsg.height,
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|