|
From: <jl...@us...> - 2008-11-19 22:17:17
|
Revision: 7010
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=7010&view=rev
Author: jleibs
Date: 2008-11-19 22:17:12 +0000 (Wed, 19 Nov 2008)
Log Message:
-----------
Making dcam_node output pointclouds correctly. Fixing segfault condition due to uninitialized memory in dcam. Adding roslaunch example to stereo_view.
Modified Paths:
--------------
pkg/trunk/drivers/cam/dcam/CMakeLists.txt
pkg/trunk/drivers/cam/dcam/Makefile.standalone
pkg/trunk/drivers/cam/dcam/src/image.cpp
pkg/trunk/drivers/cam/dcam_node/CMakeLists.txt
pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
pkg/trunk/image_msgs/include/image_msgs/CvBridge.h
pkg/trunk/vision/stereo_view/stereo_view.cpp
Added Paths:
-----------
pkg/trunk/vision/stereo_view/stereo.launch
Modified: pkg/trunk/drivers/cam/dcam/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/cam/dcam/CMakeLists.txt 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/drivers/cam/dcam/CMakeLists.txt 2008-11-19 22:17:12 UTC (rev 7010)
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-set(ROS_BUILD_TYPE Release)
+set(ROS_BUILD_TYPE RelWithDebInfo)
rospack(dcam)
@@ -17,5 +17,5 @@
rospack_add_executable(acquire src/acquire.cpp)
target_link_libraries(acquire dcam fltk)
-rospack_add_executable(stacquire src/stacquire.cpp src/imwin.cpp)
-target_link_libraries(stacquire dcam fltk)
\ No newline at end of file
+rospack_add_executable(stacquire src/stacquire.cpp src/imwin.cpp src/im3Dwin.cpp)
+target_link_libraries(stacquire dcam fltk fltk_gl glut)
\ No newline at end of file
Modified: pkg/trunk/drivers/cam/dcam/Makefile.standalone
===================================================================
--- pkg/trunk/drivers/cam/dcam/Makefile.standalone 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/drivers/cam/dcam/Makefile.standalone 2008-11-19 22:17:12 UTC (rev 7010)
@@ -10,7 +10,7 @@
CFLAGS = -DGCC -msse2 -g -O3 -mpreferred-stack-boundary=4 -Wall -Iinclude -I/usr/local/include
GCC = g++
#LDFLAGS = -Lbin -ldcam -ldc1394 -lcv -lhighgui -lfltk
-LDFLAGS = -Llib -ldcam -ldc1394 -lcv -lhighgui -lfltk -lfltk_gl -Wl,-rpath,$(shell rospack find opencv_latest)/opencv/lib -L$(shell rospack find opencv_latest)/opencv/lib -L$(shell rospack find libdc1394v2)/libdc1394v2/lib -Wl,-rpath,$(shell rospack find libdc1394v2)/libdc1394v2/lib -Wl,-rpath,$(shell rospack find dcam)/lib
+LDFLAGS = -Llib -ldcam -ldc1394 -lcv -lhighgui -lfltk -lfltk_gl -lglut -Wl,-rpath,$(shell rospack find opencv_latest)/opencv/lib -L$(shell rospack find opencv_latest)/opencv/lib -L$(shell rospack find libdc1394v2)/libdc1394v2/lib -Wl,-rpath,$(shell rospack find libdc1394v2)/libdc1394v2/lib -Wl,-rpath,$(shell rospack find dcam)/lib
SHAREDFLAGS = -shared -Wl,-soname,
Modified: pkg/trunk/drivers/cam/dcam/src/image.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam/src/image.cpp 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/drivers/cam/dcam/src/image.cpp 2008-11-19 22:17:12 UTC (rev 7010)
@@ -273,6 +273,7 @@
// point array/vector
numPts = 0;
imPts = NULL;
+ imPtsColor = NULL;
isPtArray = false;
imPtsSize = 0;
}
Modified: pkg/trunk/drivers/cam/dcam_node/CMakeLists.txt
===================================================================
--- pkg/trunk/drivers/cam/dcam_node/CMakeLists.txt 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/drivers/cam/dcam_node/CMakeLists.txt 2008-11-19 22:17:12 UTC (rev 7010)
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 2.6)
include(rosbuild)
-set(ROS_BUILD_TYPE Release)
+set(ROS_BUILD_TYPE RelWithDebInfo)
rospack(dcam_node)
rospack_add_executable(dcam_node dcam_node.cpp)
Modified: pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/drivers/cam/dcam_node/dcam_node.cpp 2008-11-19 22:17:12 UTC (rev 7010)
@@ -71,6 +71,7 @@
public:
static dcam::Dcam* cam_;
+ static cam::StereoDcam* stcam_;
DcamNode() : ros::node("dcam"), diagnostic_(this), count_(0)
@@ -204,7 +205,8 @@
// is definitely wrong.
if (stereo_cam_)
{
- cam_ = new cam::StereoDcam(guid);
+ stcam_ = new cam::StereoDcam(guid);
+ cam_ = stcam_;
cam_->setFormat(mode, fps, speed);
cam_->setProcMode(videre_mode);
} else {
@@ -213,6 +215,10 @@
}
cam_->start();
+
+ cam_->setUniqueThresh(12);
+ cam_->setTextureThresh(10);
+
serviceCam();
printf("Advertising\n");
advertiseCam();
@@ -237,19 +243,22 @@
if (do_rectify_)
{
- ( (cam::StereoDcam*)(cam_) )->doRectify();
+ // ( (cam::StereoDcam*)(cam_) )->doRectify();
+ stcam_->doRectify();
}
// cam_->doRectify();
if (do_stereo_)
{
- ( (cam::StereoDcam*)(cam_) )->doDisparity();
+ // ( (cam::StereoDcam*)(cam_) )->doDisparity();
+ stcam_->doDisparity();
}
if (do_calc_points_)
{
- ( (cam::StereoDcam*)(cam_) )->doCalcPts();
+ //( (cam::StereoDcam*)(cam_) )->doCalcPts();
+ stcam_->doCalcPts();
}
count_++;
@@ -511,6 +520,7 @@
};
dcam::Dcam* DcamNode::cam_ = 0;
+cam::StereoDcam* DcamNode::stcam_ = 0;
void sigsegv_handler(int sig)
{
Modified: pkg/trunk/image_msgs/include/image_msgs/CvBridge.h
===================================================================
--- pkg/trunk/image_msgs/include/image_msgs/CvBridge.h 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/image_msgs/include/image_msgs/CvBridge.h 2008-11-19 22:17:12 UTC (rev 7010)
@@ -112,7 +112,15 @@
reallocCvtIfNeeded(cvGetSize(rosimg_), IPL_DEPTH_8U, 3);
cvCvtColor(rosimg_, cvtimg_, CV_RGB2BGR);
img_ = cvtimg_;
- } else {
+ }
+ else if (encoding == "bgr" && rosimg.encoding == "mono" )
+ {
+ reallocCvtIfNeeded(cvGetSize(rosimg_), IPL_DEPTH_8U, 3);
+ cvCvtColor(rosimg_, cvtimg_, CV_GRAY2BGR);
+ img_ = cvtimg_;
+ }
+ else
+ {
return false;
}
}
Added: pkg/trunk/vision/stereo_view/stereo.launch
===================================================================
--- pkg/trunk/vision/stereo_view/stereo.launch (rev 0)
+++ pkg/trunk/vision/stereo_view/stereo.launch 2008-11-19 22:17:12 UTC (rev 7010)
@@ -0,0 +1,19 @@
+<launch>
+ <node name="dcam" pkg="dcam_node" type="dcam_node" respawn="false">
+ <!-- video_mode should be one of the following:
+ 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_disparity_raw"/>
+ <param name="do_stereo" type="bool" value="True"/>
+ </node>
+ <node name="stereo_view" pkg="stereo_view" type="stereo_view" respawn="false">
+ <!-- Remove this parameter to subscribe to mono images instead -->
+ <param name="subscribe_color" type="bool" value="True"/>
+ </node>
+</launch>
+
Modified: pkg/trunk/vision/stereo_view/stereo_view.cpp
===================================================================
--- pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-11-19 22:16:33 UTC (rev 7009)
+++ pkg/trunk/vision/stereo_view/stereo_view.cpp 2008-11-19 22:17:12 UTC (rev 7010)
@@ -54,6 +54,7 @@
image_msgs::Image limage;
image_msgs::Image rimage;
image_msgs::Image dimage;
+ image_msgs::StereoInfo stinfo;
image_msgs::CvBridge lbridge;
image_msgs::CvBridge rbridge;
@@ -61,15 +62,26 @@
TopicSynchronizer<StereoView> sync;
- StereoView() : ros::node("cv_view"), sync(this, &StereoView::image_cb_all, ros::Duration(0.05), &StereoView::image_cb_timeout)
+ bool subscribe_color_;
+
+ StereoView() : ros::node("cv_view"), sync(this, &StereoView::image_cb_all, ros::Duration(0.05), &StereoView::image_cb_timeout), subscribe_color_(false)
{
cvNamedWindow("left", CV_WINDOW_AUTOSIZE);
cvNamedWindow("right", CV_WINDOW_AUTOSIZE);
cvNamedWindow("disparity", CV_WINDOW_AUTOSIZE);
- sync.subscribe("dcam/left/image_rect_color", limage, 1);
- sync.subscribe("dcam/right/image_rect_color", rimage, 1);
+ param("~subscribe_color", subscribe_color_, false);
+
+ if (subscribe_color_)
+ {
+ sync.subscribe("dcam/left/image_rect_color", limage, 1);
+ sync.subscribe("dcam/right/image_rect_color", rimage, 1);
+ } else {
+ sync.subscribe("dcam/left/image_rect", limage, 1);
+ sync.subscribe("dcam/right/image_rect", rimage, 1);
+ }
sync.subscribe("dcam/disparity", dimage, 1);
+ sync.subscribe("dcam/stereo_info", stinfo, 1);
}
void image_cb_all(ros::Time t)
@@ -84,7 +96,7 @@
{
// Disparity has to be scaled to be be nicely displayable
IplImage* disp = cvCreateImage(cvGetSize(dbridge.toIpl()), IPL_DEPTH_8U, 1);
- cvCvtScale(dbridge.toIpl(), disp, 1/4.0);
+ cvCvtScale(dbridge.toIpl(), disp, 4.0/stinfo.dpp);
cvShowImage("disparity", disp);
cvReleaseImage(&disp);
}
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|