|
From: <vij...@us...> - 2009-06-23 03:34:52
|
Revision: 17485
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17485&view=rev
Author: vijaypradeep
Date: 2009-06-23 03:34:46 +0000 (Tue, 23 Jun 2009)
Log Message:
-----------
Changing namespacing for stereodcam, stereoproc, and associated launch files
Modified Paths:
--------------
pkg/trunk/calibration/kinematic_calibration/demo/videre.launch
pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.launch
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.machine
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.launch
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.machine
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.launch
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.machine
pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp
Added Paths:
-----------
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/stereo.launch
pkg/trunk/vision/stereo_image_proc/stereoproc.launch
Removed Paths:
-------------
pkg/trunk/vision/stereo_image_proc/stereo.launch
Modified: pkg/trunk/calibration/kinematic_calibration/demo/videre.launch
===================================================================
--- pkg/trunk/calibration/kinematic_calibration/demo/videre.launch 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/calibration/kinematic_calibration/demo/videre.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -4,7 +4,7 @@
-->
<param name="videre_mode" type="str" value="rectified"/>
<!-- params for the stereo_image_proc node -->
- <param name="exposure" type="int" value="0"/>
+ <param name="exposure" type="int" value="20"/>
<param name="exposure_auto" type="bool" value="false"/>
<!-- <param name="brightness" type="int" value="5"/ -->
Modified: pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp 2009-06-23 03:34:46 UTC (rev 17485)
@@ -163,8 +163,6 @@
std_msgs::Empty check_params_msg_;
- std::string stereo_name_;
-
public:
dcam::StereoDcam* stcam_;
@@ -184,30 +182,28 @@
diagnostic_.add( timestamp_diag_ );
diagnostic_.addUpdater( &StereoDcamNode::freqStatus );
- stereo_name_ = mapName("stereo") + std::string("/");
-
// If there is a camera...
if (num_cams > 0)
{
// Check our gui parameter, or else use first camera
uint64_t guid;
- if (hasParam(stereo_name_+ std::string("guid")))
+ if (hasParam("~guid"))
{
string guid_str;
- getParam(stereo_name_ + std::string("guid"), guid_str);
+ getParam("~guid", guid_str);
guid = strtoll(guid_str.c_str(), NULL, 16);
} else {
guid = dcam::getGuid(0);
}
- param(stereo_name_ + std::string("frame_id"), frame_id_, string("stereo"));
+ param("~frame_id", frame_id_, string("stereo"));
// Get the ISO speed parameter if available
string str_speed;
dc1394speed_t speed;
- param(stereo_name_ + std::string("speed"), str_speed, string("S400"));
+ param("~speed", str_speed, string("S400"));
if (str_speed == string("S100"))
speed = DC1394_ISO_SPEED_100;
else if (str_speed == string("S200"))
@@ -218,7 +214,7 @@
// Get the FPS parameter if available;
double dbl_fps;
dc1394framerate_t fps;
- param(stereo_name_ + std::string("fps"), dbl_fps, 30.0);
+ param("~fps", dbl_fps, 30.0);
desired_freq_ = dbl_fps;
if (dbl_fps >= 240.0)
fps = DC1394_FRAMERATE_240;
@@ -243,7 +239,7 @@
// Get the videre processing mode if available:
string str_videre_mode;
videre_proc_mode_t videre_mode = PROC_MODE_NONE;
- param(stereo_name_ + std::string("videre_mode"), str_videre_mode, string("none"));
+ param("~videre_mode", str_videre_mode, string("none"));
if (str_videre_mode == string("rectified"))
videre_mode = PROC_MODE_RECTIFIED;
else if (str_videre_mode == string("disparity"))
@@ -259,14 +255,14 @@
// Fetch the camera string and send it to the parameter server if people want it (they shouldn't)
std::string params(stcam_->getParameters());
- setParam(stereo_name_ + std::string("params"), params);
+ setParam("~params", params);
- setParam(stereo_name_ + std::string("exposure_max"), (int)stcam_->expMax);
- setParam(stereo_name_ + std::string("exposure_min"), (int)stcam_->expMin);
- setParam(stereo_name_ + std::string("gain_max"), (int)stcam_->gainMax);
- setParam(stereo_name_ + std::string("gain_min"), (int)stcam_->gainMin);
- setParam(stereo_name_ + std::string("brightness_max"), (int)stcam_->brightMax);
- setParam(stereo_name_ + std::string("brightness_min"), (int)stcam_->brightMin);
+ setParam("~exposure_max", (int)stcam_->expMax);
+ setParam("~exposure_min", (int)stcam_->expMin);
+ setParam("~gain_max", (int)stcam_->gainMax);
+ setParam("~gain_min", (int)stcam_->gainMin);
+ setParam("~brightness_max", (int)stcam_->brightMax);
+ setParam("~brightness_min", (int)stcam_->brightMin);
// Configure camera
stcam_->setFormat(mode, fps, speed);
@@ -277,9 +273,9 @@
stcam_->setSpeckleDiff(10);
stcam_->setCompanding(true);
- advertise<image_msgs::RawStereo>(stereo_name_ + std::string("raw_stereo"), 1);
+ advertise<image_msgs::RawStereo>("raw_stereo", 1);
- subscribe(stereo_name_ + std::string("check_params"), check_params_msg_, &StereoDcamNode::checkParams, 1);
+ subscribe("~check_params", check_params_msg_, &StereoDcamNode::checkParams, 1);
// Start the camera
stcam_->start();
@@ -302,32 +298,32 @@
void checkAndSetAll()
{
- checkAndSetIntBool("exposure", boost::bind(&dcam::Dcam::setExposure, stcam_, _1, _2));
- checkAndSetIntBool("gain", boost::bind(&dcam::Dcam::setGain, stcam_, _1, _2));
- checkAndSetIntBool("brightness", boost::bind(&dcam::Dcam::setBrightness, stcam_, _1, _2));
- checkAndSetBool("companding", boost::bind(&dcam::Dcam::setCompanding, stcam_, _1));
- checkAndSetBool("hdr", boost::bind(&dcam::Dcam::setHDR, stcam_, _1));
- checkAndSetBool("unique_check", boost::bind(&dcam::StereoDcam::setUniqueCheck, stcam_, _1));
- checkAndSetInt("texture_thresh", boost::bind(&dcam::StereoDcam::setTextureThresh, stcam_, _1));
- checkAndSetInt("unique_thresh", boost::bind(&dcam::StereoDcam::setUniqueThresh, stcam_, _1));
- checkAndSetInt("smoothness_thresh", boost::bind(&dcam::StereoDcam::setSmoothnessThresh, stcam_, _1));
- checkAndSetInt("horopter", boost::bind(&dcam::StereoDcam::setHoropter, stcam_, _1));
- checkAndSetInt("speckle_size", boost::bind(&dcam::StereoDcam::setSpeckleSize, stcam_, _1));
- checkAndSetInt("speckle_diff", boost::bind(&dcam::StereoDcam::setSpeckleDiff, stcam_, _1));
- checkAndSetInt("corr_size", boost::bind(&dcam::StereoDcam::setCorrsize, stcam_, _1));
- checkAndSetInt("num_disp", boost::bind(&dcam::StereoDcam::setNumDisp, stcam_, _1));
+ checkAndSetIntBool("~exposure", boost::bind(&dcam::Dcam::setExposure, stcam_, _1, _2));
+ checkAndSetIntBool("~gain", boost::bind(&dcam::Dcam::setGain, stcam_, _1, _2));
+ checkAndSetIntBool("~brightness", boost::bind(&dcam::Dcam::setBrightness, stcam_, _1, _2));
+ checkAndSetBool("~companding", boost::bind(&dcam::Dcam::setCompanding, stcam_, _1));
+ checkAndSetBool("~hdr", boost::bind(&dcam::Dcam::setHDR, stcam_, _1));
+ checkAndSetBool("~unique_check", boost::bind(&dcam::StereoDcam::setUniqueCheck, stcam_, _1));
+ checkAndSetInt("~texture_thresh", boost::bind(&dcam::StereoDcam::setTextureThresh, stcam_, _1));
+ checkAndSetInt("~unique_thresh", boost::bind(&dcam::StereoDcam::setUniqueThresh, stcam_, _1));
+ checkAndSetInt("~smoothness_thresh", boost::bind(&dcam::StereoDcam::setSmoothnessThresh, stcam_, _1));
+ checkAndSetInt("~horopter", boost::bind(&dcam::StereoDcam::setHoropter, stcam_, _1));
+ checkAndSetInt("~speckle_size", boost::bind(&dcam::StereoDcam::setSpeckleSize, stcam_, _1));
+ checkAndSetInt("~speckle_diff", boost::bind(&dcam::StereoDcam::setSpeckleDiff, stcam_, _1));
+ checkAndSetInt("~corr_size", boost::bind(&dcam::StereoDcam::setCorrsize, stcam_, _1));
+ checkAndSetInt("~num_disp", boost::bind(&dcam::StereoDcam::setNumDisp, stcam_, _1));
}
void checkAndSetIntBool(std::string param_name, boost::function<void(int, bool)> setfunc)
{
- if (hasParam(stereo_name_ + param_name) || hasParam(stereo_name_ + param_name + std::string("_auto")))
+ if (hasParam(param_name) || hasParam(param_name + std::string("_auto")))
{
int val = 0;
bool isauto = false;
- param( stereo_name_ + param_name, val, 0);
- param( stereo_name_ + param_name + std::string("_auto"), isauto, false);
+ param( param_name, val, 0);
+ param( param_name + std::string("_auto"), isauto, false);
int testval = (val * (!isauto));
@@ -343,11 +339,11 @@
void checkAndSetBool(std::string param_name, boost::function<bool(bool)> setfunc)
{
- if (hasParam(stereo_name_ + param_name))
+ if (hasParam(param_name))
{
bool on = false;
- param(stereo_name_ + param_name, on, false);
+ param(param_name, on, false);
std::map<std::string, int>::iterator cacheval = paramcache_.find(param_name);
@@ -362,12 +358,12 @@
void checkAndSetInt(std::string param_name, boost::function<bool(int)> setfunc)
{
- if (hasParam(stereo_name_ + param_name))
+ if (hasParam(param_name))
{
int val = 0;
- param(stereo_name_ + param_name, val, 0);
+ param( param_name, val, 0);
std::map<std::string, int>::iterator cacheval = paramcache_.find(param_name);
@@ -409,7 +405,7 @@
// Doing this as a stopgap
// measure.
timestamp_diag_.tick(raw_stereo_.header.stamp);
- publish(stereo_name_ + std::string("raw_stereo"), raw_stereo_);
+ publish("raw_stereo", raw_stereo_);
count_++;
return true;
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.launch 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -47,16 +47,8 @@
<param name="imu/autocalibrate" type="bool" value="true" />
<node machine="four" pkg="imu_node" type="imu_node" output="screen"/>
-<!-- Stereo cam
- <node machine="four" pkg="dcam" type="stereodcam" name="stereodcam" args="">
- <param name="videre_mode" type="string" value="disparity_raw" />
- <param name="fps" type="double" value="15.0"/>
- <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="frame_id" type="string" value="stereo_optical_frame"/>
-</node>
--->
+<!-- Videre Stereo cam -->
+ <include file="$(find pr2_alpha)/stereo.launch" />
<!-- Sound -->
<node pkg="sound_play" type="soundplay_node.py" machine="three" />
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.machine
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.machine 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/pre.machine 2009-06-23 03:34:46 UTC (rev 17485)
@@ -2,7 +2,8 @@
<machine name="realtime_root" user="root" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>
<machine name="realtime" address="pre1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="two" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
- <machine name="three" address="pre3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="four" address="pre4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="two" address="pre2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
+ <machine name="three" address="pre3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="four" address="pre4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="stereo" address="pre4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.launch 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -47,22 +47,8 @@
<param name="imu/autocalibrate" type="bool" value="true" />
<node machine="four" pkg="imu_node" type="imu_node" output="screen"/>
-<!-- Stereo cam -->
- <group ns="stereo">
- <param name="videre_mode" type="str" value="none"/>
- <param name="do_colorize" type="bool" value="True"/>
- <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"/>
- <param name="fps" type="double" value="15.0"/>
- <param name="frame_id" type="string" value="stereo_optical_frame"/>
- <param name="exposure_auto" type="bool" value="true"/>
- <param name="brightness_auto" type="bool" value="true"/>
- <param name="gain_auto" type="bool" value="true"/>
- <param name="num_disp" value="128"/>
- </group>
- <node machine="four" pkg="dcam" type="stereodcam" respawn="false"/>
+ <!-- Videre Stereo cam -->
+ <include file="$(find pr2_alpha)/stereo.launch" />
<!-- Prosilica camera setup -->
<group ns="prosilica">
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.machine
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.machine 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prf.machine 2009-06-23 03:34:46 UTC (rev 17485)
@@ -5,4 +5,7 @@
<machine name="two" address="prf2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true" />
<machine name="three" address="prf3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
<machine name="four" address="prf4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+
+ <!-- Defines the machine that the Videre Stereocam is attached to -->
+ <machine name="stereo" address="prf4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.launch 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -76,17 +76,8 @@
<node pkg="runtime_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="three"/>
<node pkg="runtime_monitor" type="disk_usage.py" args="$(optenv HOME /home)" machine="four"/>
-<!-- Stereo cam -->
- <group ns="stereo">
- <param name="videre_mode" type="str" value="none"/>
- <param name="exposure_auto" type="bool" value="True" />
- <param name="gain_auto" type="bool" value="True" />
- <param name="brightness_auto" type="bool" value="True" />
- <param name="fps" type="double" value="15.0"/>
- <param name="frame_id" type="string" value="stereo_optical_frame"/>
- <param name="num_disp" value="128"/>
- </group>
- <node machine="four" pkg="dcam" type="stereodcam" respawn="false"/>
+ <!-- Videre Stereo cam -->
+ <include file="$(find pr2_alpha)/stereo.launch" />
<!-- Plug to chessboard offsets -->
<group ns="plug_detector">
Modified: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.machine
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.machine 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/prg.machine 2009-06-23 03:34:46 UTC (rev 17485)
@@ -2,7 +2,8 @@
<machine name="realtime_root" user="root" address="prg1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never" />
<machine name="realtime" address="prg1" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="two" address="prg2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
- <machine name="three" address="prg3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
- <machine name="four" address="prg4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="two" address="prg2" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="true"/>
+ <machine name="three" address="prg3" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="four" address="prg4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
+ <machine name="stereo" address="prg4" ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />
</launch>
Added: pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/stereo.launch
===================================================================
--- pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/stereo.launch (rev 0)
+++ pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_alpha/stereo.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -0,0 +1,35 @@
+<launch>
+ <!-- Brings up the stereocam on the PR2. Since the machine
+ tag is definied, this file needs to be included as part
+ of a launch file that defines the machine (ie. prx.launch) -->
+
+ <group ns="stereo">
+ <!-- Start the 1394 videre camera driver -->
+ <node machine="stereo" pkg="dcam" type="stereodcam" respawn="false" >
+ <param name="videre_mode" type="str" value="none"/>
+ <param name="fps" type="double" value="4.0"/>
+ <param name="frame_id" type="string" value="stereo_optical_frame"/>
+ <param name="exposure_auto" type="bool" value="true"/>
+ <param name="brightness_auto" type="bool" value="true"/>
+ <param name="gain_auto" type="bool" value="true"/>
+ </node>
+
+ <!-- Start the stereo processing node -->
+ <!-- This can be run on any machine, but running
+ it on the same machine as stereodcam reduces network latency -->
+
+ <!-- Probably don't want to autostart stereoproc right now, since it's not a hardware driver -->
+
+ <!--
+ <node machine="stereo" pkg="stereo_image_proc" type="stereoproc"
+ respawn="false" output="screen" name="stereoproc">
+ <param name="do_colorize" type="bool" value="True"/>
+ <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>
Modified: pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp
===================================================================
--- pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp 2009-06-23 03:34:46 UTC (rev 17485)
@@ -75,28 +75,23 @@
string frame_id_;
- std::string stereo_name_;
-
public:
cam::StereoData* stdata_;
StereoProc() : ros::Node("stereoproc"), diagnostic_(this), count_(0), stdata_(NULL)
{
-
- stereo_name_ = mapName("stereo") + std::string("/");
-
diagnostic_.addUpdater( &StereoProc::freqStatus );
- param(stereo_name_ + std::string("do_colorize"), do_colorize_, false);
+ param("~do_colorize", do_colorize_, false);
- param(stereo_name_ + std::string("do_rectify"), do_rectify_, false);
+ param("~do_rectify", do_rectify_, false);
- param(stereo_name_ + std::string("do_stereo"), do_stereo_, false);
+ param("~do_stereo", do_stereo_, false);
- param(stereo_name_ + std::string("do_calc_points"), do_calc_points_, false);
+ param("~do_calc_points", do_calc_points_, false);
- param(stereo_name_ + std::string("do_keep_coords"), do_keep_coords_, false);
+ param("~do_keep_coords", do_keep_coords_, false);
if (do_keep_coords_) {
ROS_INFO("I'm keeping the image coordonate in the point cloud\n");
@@ -115,38 +110,38 @@
// stdata_->setSpeckleDiff(10);
int unique_thresh;
- param(stereo_name_ + "unique_thresh", unique_thresh, 36);
+ param("~unique_thresh", unique_thresh, 36);
stdata_->setTextureThresh(unique_thresh);
int texture_thresh;
- param(stereo_name_ + "texture_thresh", texture_thresh, 30);
+ param("~texture_thresh", texture_thresh, 30);
stdata_->setUniqueThresh(texture_thresh);
int speckle_size;
- param(stereo_name_ + "speckle_size", speckle_size, 100);
+ param("~speckle_size", speckle_size, 100);
stdata_->setSpeckleRegionSize(speckle_size);
int speckle_diff;
- param(stereo_name_ + "speckle_diff", speckle_diff, 10);
+ param("~speckle_diff", speckle_diff, 10);
stdata_->setSpeckleDiff(speckle_diff);
int smoothness_thresh;
- if (getParam(stereo_name_ + "smoothness_thresh", smoothness_thresh))
+ if (getParam("~smoothness_thresh", smoothness_thresh))
stdata_->setSmoothnessThresh(smoothness_thresh);
int horopter;
- if (getParam(stereo_name_ + "horopter", horopter))
+ if (getParam("~horopter", horopter))
stdata_->setHoropter(horopter);
int corr_size;
- if (getParam(stereo_name_ + "corr_size", corr_size))
+ if (getParam("~corr_size", corr_size))
stdata_->setCorrSize(corr_size);
int num_disp;
- if (getParam(stereo_name_ + "num_disp", num_disp))
+ if (getParam("~num_disp", num_disp))
stdata_->setNumDisp(num_disp);
- subscribe(stereo_name_ + std::string("raw_stereo"), raw_stereo_, &StereoProc::rawCb, 1);
+ subscribe("raw_stereo", raw_stereo_, &StereoProc::rawCb, 1);
}
~StereoProc()
@@ -190,8 +185,8 @@
void publishCam()
{
- publishImages(stereo_name_ + std::string("left/"), stdata_->imLeft);
- publishImages(stereo_name_ + std::string("right/"), stdata_->imRight);
+ publishImages("left/", stdata_->imLeft);
+ publishImages("right/", stdata_->imRight);
if (stdata_->hasDisparity)
{
@@ -217,7 +212,7 @@
disparity_info_.speckle_region_size = stdata_->speckleRegionSize;
disparity_info_.unique_check = stdata_->unique_check;
- publish(stereo_name_ + std::string("disparity_info"), disparity_info_);
+ publish("disparity_info", disparity_info_);
fillImage(img_, "disparity",
stdata_->imHeight, stdata_->imWidth, 1,
@@ -226,7 +221,7 @@
img_.header.stamp = raw_stereo_.header.stamp;
img_.header.frame_id = raw_stereo_.header.frame_id;
- publish(stereo_name_ + std::string("disparity"), img_);
+ publish("disparity", img_);
}
if (do_calc_points_)
@@ -266,7 +261,7 @@
}
}
- publish(stereo_name_ + std::string("cloud"), cloud_);
+ publish("cloud", cloud_);
}
stereo_info_.header.stamp = raw_stereo_.header.stamp;
@@ -278,7 +273,7 @@
memcpy((char*)(&stereo_info_.Om[0]), (char*)(stdata_->Om), 3*sizeof(double));
memcpy((char*)(&stereo_info_.RP[0]), (char*)(stdata_->RP), 16*sizeof(double));
- publish(stereo_name_ + std::string("stereo_info"), stereo_info_);
+ publish("stereo_info", stereo_info_);
}
void publishImages(std::string base_name, cam::ImageData* img_data)
@@ -391,19 +386,19 @@
void advertiseCam()
{
- advertise<image_msgs::StereoInfo>(stereo_name_ + std::string("stereo_info"), 1);
+ advertise<image_msgs::StereoInfo>("stereo_info", 1);
- advertiseImages(stereo_name_ + std::string("left/"), stdata_->imLeft);
- advertiseImages(stereo_name_ + std::string("right/"), stdata_->imRight);
+ advertiseImages("left/", stdata_->imLeft);
+ advertiseImages("right/", stdata_->imRight);
if (stdata_->hasDisparity)
{
- advertise<image_msgs::DisparityInfo>(stereo_name_ + std::string("disparity_info"), 1);
- advertise<image_msgs::Image>(stereo_name_ + std::string("disparity"), 1);
+ advertise<image_msgs::DisparityInfo>("disparity_info", 1);
+ advertise<image_msgs::Image>("disparity", 1);
}
if (do_calc_points_)
- advertise<robot_msgs::PointCloud>(stereo_name_ + std::string("cloud"),1);
+ advertise<robot_msgs::PointCloud>("cloud",1);
}
Deleted: pkg/trunk/vision/stereo_image_proc/stereo.launch
===================================================================
--- pkg/trunk/vision/stereo_image_proc/stereo.launch 2009-06-23 02:55:18 UTC (rev 17484)
+++ pkg/trunk/vision/stereo_image_proc/stereo.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -1,40 +0,0 @@
-<launch>
- <!-- videre_mode should be one of the following:
- disparity: Disparity and rectification done on chip.
- Provides: Disparity and left mono image
- disparity_raw: Disparity done on chip (debayer and rectification in software).
- Provides: disparity and left color image.
- none: No stereo on chip (all processing done in software).
- Provides: all 3 images available
- rectified: Rectification on chip
- Provides: all 3 images available but no color
- -->
- <param name="stereo/videre_mode" type="str" value="none"/>
- <param name="stereo/do_colorize" type="bool" value="True"/>
- <param name="stereo/do_rectify" type="bool" value="True"/>
- <param name="stereo/do_stereo" type="bool" value="True"/>
- <param name="stereo/do_calc_points" type="bool" value="True"/>
- <param name="stereo/do_keep_coords" type="bool" value="True"/>
-
- <!-- stereo processing parameters
- texture_thresh: Threshold for removing bad disparities based on texture
- Default value: 30
- unique_thresh: Threshold for removing bad disparities based on ambiguity
- Default value: 36
- speckle_diff: Threshold for region-growing (1/16 pixel disparity)
- Default value: 10
- speckle_size: Threshold for disparity region size (pixels)
- Default value: 100
- horopter: X offset for close-in stereo (pixels)
- Default value: 0
- corr_size: Correlation window size (pixels)
- Default value: 15
- num_disp: Number of disparities (pixels)
- Default value: 64
- -->
-
- <param name="stereo/num_disp" type="int" value="64"/>
-
- <node pkg="stereo_image_proc" type="stereoproc" respawn="false" output="screen"/>
-</launch>
-
Copied: pkg/trunk/vision/stereo_image_proc/stereoproc.launch (from rev 17442, pkg/trunk/vision/stereo_image_proc/stereo.launch)
===================================================================
--- pkg/trunk/vision/stereo_image_proc/stereoproc.launch (rev 0)
+++ pkg/trunk/vision/stereo_image_proc/stereoproc.launch 2009-06-23 03:34:46 UTC (rev 17485)
@@ -0,0 +1,40 @@
+<launch>
+ <!-- videre_mode should be one of the following:
+ disparity: Disparity and rectification done on chip.
+ Provides: Disparity and left mono image
+ disparity_raw: Disparity done on chip (debayer and rectification in software).
+ Provides: disparity and left color image.
+ none: No stereo on chip (all processing done in software).
+ Provides: all 3 images available
+ rectified: Rectification on chip
+ Provides: all 3 images available but no color
+ -->
+ <!-- stereo processing parameters
+ texture_thresh: Threshold for removing bad disparities based on texture
+ Default value: 30
+ unique_thresh: Threshold for removing bad disparities based on ambiguity
+ Default value: 36
+ speckle_diff: Threshold for region-growing (1/16 pixel disparity)
+ Default value: 10
+ speckle_size: Threshold for disparity region size (pixels)
+ Default value: 100
+ horopter: X offset for close-in stereo (pixels)
+ Default value: 0
+ corr_size: Correlation window size (pixels)
+ Default value: 15
+ num_disp: Number of disparities (pixels)
+ Default value: 64
+ -->
+ <group ns="stereo">
+ <node pkg="stereo_image_proc" type="stereoproc" respawn="false" output="screen" name="stereoproc">
+ <param name="videre_mode" type="str" value="none"/>
+ <param name="do_colorize" type="bool" value="True"/>
+ <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"/>
+ <param name="num_disp" type="int" value="64"/>
+ </node>
+ </group>
+</launch>
+
Property changes on: pkg/trunk/vision/stereo_image_proc/stereoproc.launch
___________________________________________________________________
Added: svn:mergeinfo
+ /pkg/branches/gazebo-branch-merge/vision/stereo_image_proc/stereo.launch:15683-15684,15739-15794,15797-15820,15822-15839,15852-15870,15983-16008,16010-16016,16129-16141,16145-16169,16245-16262,16274-16334
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|