00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00033 #ifndef _XB3_CPP_
00034 #define _XB3_CPP_
00035
00036 #include "xb3.h"
00037
00042 void clean_dc1394(void)
00043 {
00044 printf("asdsad=%p\n", t_dc1394.camera);
00045 printf("asdsad=%p\n", t_dc1394.camera);
00046 printf("asdsad=%p\n", t_dc1394.camera);
00047 printf("asdsad=%p\n", t_dc1394.camera);
00048 printf("asdsad=%p\n", t_dc1394.camera);
00049 printf("asdsad=%p\n", t_dc1394.camera);
00050
00051 dc1394_capture_stop(t_dc1394.camera);
00052
00053 ROS_WARN("stopping camera capture\n");
00054
00055 dc1394_video_set_transmission(t_dc1394.camera, DC1394_OFF );
00056
00057 dc1394_camera_free( t_dc1394.camera );
00058 }
00059
00060
00066 void signal_handler(int sig)
00067 {
00068 printf("%d %d %d\n",sig,SIGSEGV,SIGINT);
00069
00070 if(sig==SIGSEGV)
00071 {
00072
00073 signal(SIGSEGV, SIG_DFL);
00074
00075 ROS_WARN("System segfaulted");
00076
00077 clean_dc1394();
00078 ros::shutdown();
00079
00080 exit(0);
00081 }
00082 else if(sig==SIGINT)
00083 {
00084 ROS_WARN("Ctrl-c pressed");
00085
00086 clean_dc1394();
00087 ros::shutdown();
00088
00089 exit(0);
00090 }
00091 }
00092
00093
00102 int init_camera(dc1394_t * d, PGRStereoCamera_t* stereoCamera, dc1394camera_t** camera, unsigned int nThisCam)
00103
00104 {
00105 dc1394camera_list_t * list;
00106 dc1394error_t err;
00107
00108
00109 d = dc1394_new ();
00110
00111
00112 err = dc1394_camera_enumerate (d, &list);
00113
00114 if ( err != DC1394_SUCCESS )
00115 {
00116 fprintf( stderr, "Unable to look for cameras\n\n"
00117 "Please check \n"
00118 " - if the kernel modules `ieee1394',`raw1394' and `ohci1394' are loaded \n"
00119 " - if you have read/write access to /dev/raw1394\n\n");
00120 return 1;
00121 }
00122
00123
00124 if (list->num == 0)
00125 {
00126 fprintf( stderr, "No cameras found!\n"); clean_dc1394();
00127 }
00128
00129 printf( "There were %d camera(s) found attached to your PC\n", list->num );
00130
00131
00132 for ( nThisCam = 0; nThisCam < list->num; nThisCam++ )
00133 {
00134 *camera = dc1394_camera_new(d, list->ids[nThisCam].guid);
00135
00136 if(!*camera)
00137 {
00138 printf("Failed to initialize camera with guid %llx", list->ids[nThisCam].guid);
00139 continue;
00140 }
00141
00142 printf( "Camera %d model = '%s'\n", nThisCam, (*camera)->model );
00143
00144 if ( isStereoCamera(*camera))
00145 {
00146
00147 printf( "Using this camera\n" );
00148 break;
00149 }
00150
00151 dc1394_camera_free(*camera);
00152 }
00153
00154 if ( nThisCam == list->num )
00155 {
00156 printf( "No stereo cameras were detected\n" );
00157 return 0;
00158 }
00159
00160
00161
00162 err = queryStereoCamera( *camera, stereoCamera );
00163 if ( err != DC1394_SUCCESS )
00164 {
00165 fprintf( stderr, "Cannot query all information from camera\n" );
00166 clean_dc1394();
00167 }
00168
00169 if ( stereoCamera->model != BUMBLEBEEXB3 )
00170 {
00171 fprintf( stderr, "Stereo camera found was not a BB XB3\n" );
00172 clean_dc1394();
00173 }
00174
00175
00176
00177 stereoCamera->nBytesPerPixel = 3;
00178 stereoCamera->nRows = 960;
00179 stereoCamera->nCols = 1280;
00180
00181
00182 printf( "Setting stereo video capture mode\n" );
00183
00184 err = setStereoVideoCapture( stereoCamera );
00185
00186 if ( err != DC1394_SUCCESS )
00187 {
00188 fprintf( stderr, "Could not set up video capture mode\n" );
00189 clean_dc1394();
00190 }
00191
00192
00193 printf( "Start transmission\n" );
00194 err = startTransmission( stereoCamera );
00195 if ( err != DC1394_SUCCESS )
00196 {
00197 fprintf( stderr, "Unable to start camera iso transmission\n" );
00198 clean_dc1394();
00199 }
00200 return 1;}
00201
00202
00210 int copy_img_buffer_to_cvMat(unsigned char* Buffer, cv::Mat left, cv::Mat center, cv::Mat right)
00211 {
00212
00213 unsigned char* ptr_left_buffers = Buffer;
00214 unsigned char* ptr_center_buffer = Buffer + 3 * 1280*960;
00215 unsigned char* ptr_right_buffers = Buffer + 6 * 1280*960;
00216
00217
00218 unsigned char* ptr_left_cvMat = left.ptr<unsigned char>(0);
00219 unsigned char* ptr_center_cvMat = center.ptr<unsigned char>(0);
00220 unsigned char* ptr_right_cvMat = right.ptr<unsigned char>(0);
00221
00222
00223 int count=0;
00224 for(int c=0; c<1280;c++)
00225 for (int l=0; l<960; l++)
00226 {
00227
00228 ptr_left_cvMat[count] = ptr_left_buffers[count+2];
00229 ptr_left_cvMat[count+1] = ptr_left_buffers[count+1];
00230 ptr_left_cvMat[count+2] = ptr_left_buffers[count];
00231
00232 ptr_center_cvMat[count] = ptr_center_buffer[count+2];
00233 ptr_center_cvMat[count+1] = ptr_center_buffer[count+1];
00234 ptr_center_cvMat[count+2] = ptr_center_buffer[count];
00235
00236 ptr_right_cvMat[count] = ptr_right_buffers[count+2];
00237 ptr_right_cvMat[count+1] = ptr_right_buffers[count+1];
00238 ptr_right_cvMat[count+2] = ptr_right_buffers[count];
00239
00240 count+=3;
00241 }
00242 return 1;}
00243
00253 void set_fixed_fields_image_msg(sensor_msgs::Image* msg, int height, int width, char* encoding, int is_bigendian, char* frame_id)
00254 {
00255 msg->height = height;
00256 msg->width = width;
00257 msg->encoding = sensor_msgs::image_encodings::RGB8;
00258 msg->is_bigendian = 0;
00259 msg->step = width*3;
00260 msg->data.resize(width*height*3);
00261 msg->header.frame_id = frame_id;
00262
00263 }
00264
00272 void set_fixed_camera_info(sensor_msgs::CameraInfo *info, int height, int width, char* frame_id)
00273 {
00274 info->height = height;
00275 info->width = width;
00276 info->header.frame_id = frame_id;
00277 info->roi.do_rectify = true;
00278 }
00279
00286 void copy_pixels_to_image_msg_data(unsigned char *in, sensor_msgs::Image *image, int size)
00287 {
00288
00289
00290 for(int i=0; i<size; i+=3)
00291
00292
00293 {
00294
00295
00296
00297 image->data[i] = in[i+2];
00298 image->data[i+1] = in[i+1];
00299 image->data[i+2] = in[i];
00300
00301 }
00302 }
00303
00309 void reconfig(xb3::xb3Config &config, uint32_t level)
00310 {
00311 ROS_INFO("dynamic reconfigure1n");
00312 }
00313
00314 using namespace std;
00315
00316 int main(int argc, char **argv)
00317 {
00319 t_flags.debug=false;
00320 t_buffers.pucLeftRGB=NULL;
00321 t_buffers.pucCenterRGB=NULL;
00322 t_buffers.pucRightRGB=NULL;
00323
00325 ros::init(argc, argv, "xb3", ros::init_options::NoSigintHandler | ros::init_options::AnonymousName);
00326 ros::NodeHandle nh;
00327
00329 signal(SIGINT, signal_handler);
00330 signal(SIGSEGV, &signal_handler);
00331
00333
00334 int width;
00335 if (nh.hasParam("width"))
00336 {
00337 nh.getParam("width", width);
00338 }
00339 else
00340 {
00341 ROS_ERROR("Set properly an image width value. (param= 'width') ");
00342 return -1;
00343 }
00344
00345 int height;
00346 if (nh.hasParam("height"))
00347 {
00348 nh.getParam("height", height);
00349 }
00350 else
00351 {
00352 ROS_ERROR("Set properly an image height value. (param= 'height') ");
00353 return -1;
00354 }
00355
00357 set_fixed_camera_info(&t_msgs.short_left_info, height,width, (char*)(ros::names::remap("/xb3_optical_frame")).c_str());
00358 set_fixed_camera_info(&t_msgs.short_right_info, height,width, (char*)(ros::names::remap("/xb3_optical_frame")).c_str());
00359 set_fixed_camera_info(&t_msgs.wide_left_info, height,width, (char*)(ros::names::remap("/xb3_optical_frame")).c_str());
00360 set_fixed_camera_info(&t_msgs.wide_right_info, height,width, (char*)(ros::names::remap("/xb3_optical_frame")).c_str());
00361
00363 set_fixed_fields_image_msg(&t_msgs.short_left, height,width, (char*)"RGB8", 0, (char*)(ros::names::remap( "/xb3_optical_frame")).c_str());
00364 set_fixed_fields_image_msg(&t_msgs.short_right, height,width, (char*)"RGB8", 0, (char*)(ros::names::remap( "/xb3_optical_frame")).c_str());
00365 set_fixed_fields_image_msg(&t_msgs.wide_left, height,width, (char*)"RGB8", 0, (char*)(ros::names::remap( "/xb3_optical_frame")).c_str());
00366 set_fixed_fields_image_msg(&t_msgs.wide_right, height,width, (char*)"RGB8", 0, (char*)(ros::names::remap("/xb3_optical_frame")).c_str());
00367
00369 image_transport::ImageTransport it(nh);
00370 t_msgs.short_left_pub = it.advertiseCamera("short/left/image_raw", 1);
00371 t_msgs.short_right_pub = it.advertiseCamera("short/right/image_raw", 1);
00372 t_msgs.wide_left_pub = it.advertiseCamera("wide/left/image_raw", 1);
00373 t_msgs.wide_right_pub = it.advertiseCamera("wide/right/image_raw", 1);
00374
00375
00376 t_msgs.short_left_info_manager = new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh, "short/left"),"short/left","package://xb3/calibrations/short_left.yaml");
00377 t_msgs.short_right_info_manager = new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh, "short/right"),"short/right", "package://xb3/calibrations/short_right.yaml");
00378 t_msgs.wide_left_info_manager = new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh, "wide/left"),"wide/left","package://xb3/calibrations/wide_left.yaml");
00379 t_msgs.wide_right_info_manager = new camera_info_manager::CameraInfoManager(ros::NodeHandle(nh, "wide/right"),"wide/right","package://xb3/calibrations/wide_right.yaml");
00380
00381
00382
00383
00384
00385
00386
00388 init_camera(t_dc1394.d, &t_dc1394.stereoCamera,&t_dc1394.camera, t_dc1394.nThisCam );
00389 PFLN
00390 ROS_INFO("Connected to XB3 camera");
00391
00393 t_buffers.nBufferSize = t_dc1394.stereoCamera.nRows * t_dc1394.stereoCamera.nCols * t_dc1394.stereoCamera.nBytesPerPixel;
00394 t_buffers.pucDeInterlacedBuffer = new unsigned char[ t_buffers.nBufferSize ];
00395 t_buffers.pucRGBBuffer = NULL;
00396 t_buffers.pucGreenBuffer = NULL;
00397
00398 t_imgs.left.create(cvSize(1280,960),CV_8UC3);
00399 t_imgs.center.create(cvSize(1280,960),CV_8UC3);
00400 t_imgs.right.create(cvSize(1280,960),CV_8UC3);
00401
00402 t_imgs.left_640_480.create(cvSize(width,height),CV_8UC3);
00403 t_imgs.center_640_480.create(cvSize(width,height),CV_8UC3);
00404 t_imgs.right_640_480.create(cvSize(width,height),CV_8UC3);
00405
00406
00407 if ( t_dc1394.stereoCamera.bColor )
00408 {
00409 t_buffers.pucRGBBuffer = new unsigned char[ 3 * t_buffers.nBufferSize ];
00410 t_buffers.pucGreenBuffer = new unsigned char[ t_buffers.nBufferSize ];
00411 }
00412 else
00413 {
00414 ROS_ERROR("This driver works only with color stereo cameras");
00415 signal_handler(SIGINT);
00416 }
00417
00419 if (t_flags.debug)
00420 {
00421 cvNamedWindow("left",CV_WINDOW_AUTOSIZE);
00422 cvNamedWindow("center",CV_WINDOW_AUTOSIZE);
00423 cvNamedWindow("right",CV_WINDOW_AUTOSIZE);
00424 }
00425
00426
00427
00428
00429 dynamic_reconfigure::Server<xb3::xb3Config> srv;
00430 dynamic_reconfigure::Server<xb3::xb3Config>::CallbackType f;
00431 f = boost::bind(&reconfig, _1, _2);
00432 srv.setCallback(f);
00433
00434 static tf::TransformBroadcaster br;
00435 tf::Transform transform;
00436 transform.setOrigin( tf::Vector3(0,-1, 0.0) );
00437 transform.setRotation( tf::Quaternion(0, 0, 0) );
00438
00439
00440 while(1)
00441 {
00442
00443 extractImagesColorXB3( &t_dc1394.stereoCamera, DC1394_BAYER_METHOD_NEAREST, t_buffers.pucDeInterlacedBuffer, t_buffers.pucRGBBuffer, t_buffers.pucGreenBuffer, &t_buffers.pucRightRGB, &t_buffers.pucLeftRGB, &t_buffers.pucCenterRGB);
00444
00445
00446 ros::Time stamp=ros::Time::now();
00447
00448 copy_img_buffer_to_cvMat(t_buffers.pucRGBBuffer, t_imgs.left, t_imgs.center, t_imgs.right);
00449
00450
00451 if (width==640 && height==480)
00452 {
00453 cv::pyrDown(t_imgs.left, t_imgs.left_640_480);
00454 cv::pyrDown(t_imgs.right, t_imgs.right_640_480);
00455 cv::pyrDown(t_imgs.center, t_imgs.center_640_480);
00456 }
00457 else if (width==1280 && height==960)
00458 {
00459 t_imgs.left_640_480=t_imgs.left;
00460 t_imgs.right_640_480=t_imgs.right;
00461 t_imgs.center_640_480=t_imgs.center;
00462 }
00463
00465
00466
00467
00468 copy_pixels_to_image_msg_data(t_imgs.left_640_480.ptr<unsigned char>(0), &t_msgs.short_left, height*width*3);
00469
00470
00471 copy_pixels_to_image_msg_data(t_imgs.center_640_480.ptr<unsigned char>(0), &t_msgs.short_right, height*width*3);
00472
00473
00474 copy_pixels_to_image_msg_data(t_imgs.left_640_480.ptr<unsigned char>(0), &t_msgs.wide_left, height*width*3);
00475
00476
00477 copy_pixels_to_image_msg_data(t_imgs.right_640_480.ptr<unsigned char>(0), &t_msgs.wide_right, height*width*3);
00478
00479
00480 t_msgs.short_left_info = t_msgs.short_left_info_manager->getCameraInfo();
00481 t_msgs.short_right_info = t_msgs.short_right_info_manager->getCameraInfo();
00482
00483 t_msgs.wide_left_info = t_msgs.wide_left_info_manager->getCameraInfo();
00484 t_msgs.wide_right_info = t_msgs.wide_right_info_manager->getCameraInfo();
00485
00486 t_msgs.short_left_info.header.frame_id = ros::names::remap("/xb3_optical_frame");
00487 t_msgs.short_right_info.header.frame_id = ros::names::remap("/xb3_optical_frame");
00488 t_msgs.wide_left_info.header.frame_id = ros::names::remap("/xb3_optical_frame");
00489 t_msgs.wide_right_info.header.frame_id = ros::names::remap("/xb3_optical_frame");
00490
00491 t_msgs.short_left_pub.publish(t_msgs.short_left, t_msgs.short_left_info, stamp);
00492 t_msgs.short_right_pub.publish(t_msgs.short_right, t_msgs.short_right_info, stamp);
00493 t_msgs.wide_left_pub.publish(t_msgs.wide_left, t_msgs.wide_left_info, stamp);
00494 t_msgs.wide_right_pub.publish(t_msgs.wide_right, t_msgs.wide_right_info, stamp);
00495
00496 if (t_flags.debug)
00497 {
00498 cv::imshow("left",t_imgs.left_640_480);
00499 cv::imshow("center",t_imgs.center_640_480);
00500 cv::imshow("right",t_imgs.right_640_480);
00501 }
00502
00503
00504
00505 ros::spinOnce();
00506
00507 if (t_flags.debug)
00508 {
00509 char k=cvWaitKey(40);
00510 if(k=='q') break;
00511 }
00512 }
00513
00514 clean_dc1394();
00515
00516 return 0;
00517 }
00518
00519 #endif
00520