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 #include <ros/ros.h>
00026 #include <image_transport/image_transport.h>
00027 #include <cv_bridge/CvBridge.h>
00028
00029
00030 #include <sensor_msgs/Image.h>
00031 #include <sensor_msgs/CameraInfo.h>
00032 #include <sensor_msgs/fill_image.h>
00033 #include <sensor_msgs/SetCameraInfo.h>
00034 #include <sensor_msgs/PointCloud.h>
00035 #include <sensor_msgs/PointCloud2.h>
00036
00037 #include <cob_camera_sensors/GetTOFImages.h>
00038
00039
00040 #include <cob_camera_sensors/AbstractRangeImagingSensor.h>
00041 #include <cob_vision_utils/CameraSensorToolbox.h>
00042 #include <cob_vision_utils/GlobalDefines.h>
00043 #include <cob_vision_utils/VisionUtils.h>
00044
00045 #include <boost/thread/mutex.hpp>
00046
00047 using namespace ipa_CameraSensors;
00048
00049 class CobTofCameraNode
00050 {
00051 enum t_Mode
00052 {
00053 MODE_TOPIC = 0,
00054 MODE_SERVICE
00055 };
00056
00057 private:
00058 ros::NodeHandle node_handle_;
00059
00060 image_transport::ImageTransport image_transport_;
00061 image_transport::CameraPublisher xyz_image_publisher_;
00062 image_transport::CameraPublisher grey_image_publisher_;
00063 ros::Publisher topicPub_pointCloud_;
00064 ros::Publisher topicPub_pointCloud2_;
00065
00066 sensor_msgs::CameraInfo camera_info_msg_;
00067
00068 ros::ServiceServer camera_info_service_;
00069 ros::ServiceServer image_service_;
00070
00071 AbstractRangeImagingSensorPtr tof_camera_;
00072
00073 std::string config_directory_;
00074 int tof_camera_index_;
00075 ipa_CameraSensors::t_cameraType tof_camera_type_;
00076 bool filter_xyz_by_amplitude_;
00077 bool filter_xyz_tearoff_edges_;
00078 int lower_amplitude_threshold_;
00079 int upper_amplitude_threshold_;
00080 double tearoff_tear_half_fraction_;
00081
00082 cv::Mat xyz_image_32F3_;
00083 cv::Mat grey_image_32F1_;
00084
00085 CobTofCameraNode::t_Mode ros_node_mode_;
00086 boost::mutex service_mutex_;
00087
00088 bool publish_point_cloud_;
00089 bool publish_point_cloud_2_;
00090
00091 public:
00093 CobTofCameraNode(const ros::NodeHandle& node_handle)
00094 : node_handle_(node_handle),
00095 image_transport_(node_handle),
00096 tof_camera_(AbstractRangeImagingSensorPtr()),
00097 xyz_image_32F3_(cv::Mat()),
00098 grey_image_32F1_(cv::Mat()),
00099 publish_point_cloud_(false),
00100 publish_point_cloud_2_(false)
00101 {
00103 }
00104
00106 ~CobTofCameraNode()
00107 {
00108 tof_camera_->Close();
00109 }
00110
00113 bool init()
00114 {
00115 if (loadParameters() == false)
00116 {
00117 ROS_ERROR("[color_camera] Could not read all parameters from launch file");
00118 return false;
00119 }
00120
00121
00122 if (tof_camera_->Init(config_directory_, tof_camera_index_) & ipa_CameraSensors::RET_FAILED)
00123 {
00124
00125 std::stringstream ss;
00126 ss << "Initialization of tof camera ";
00127 ss << tof_camera_index_;
00128 ss << " failed";
00129 ROS_ERROR("[tof_camera] %s", ss.str().c_str());
00130 tof_camera_ = AbstractRangeImagingSensorPtr();
00131 return false;
00132 }
00133
00134 if (tof_camera_->Open() & ipa_CameraSensors::RET_FAILED)
00135 {
00136 std::stringstream ss;
00137 ss << "Could not open tof camera ";
00138 ss << tof_camera_index_;
00139 ROS_ERROR("[tof_camera] %s", ss.str().c_str());
00140 tof_camera_ = AbstractRangeImagingSensorPtr();
00141 return false;
00142 }
00143
00145 ipa_CameraSensors::t_cameraProperty cameraProperty;
00146 cameraProperty.propertyID = ipa_CameraSensors::PROP_CAMERA_RESOLUTION;
00147 tof_camera_->GetProperty(&cameraProperty);
00148 int range_sensor_width = cameraProperty.cameraResolution.xResolution;
00149 int range_sensor_height = cameraProperty.cameraResolution.yResolution;
00150 cv::Size range_image_size(range_sensor_width, range_sensor_height);
00151
00153 ipa_CameraSensors::CameraSensorToolboxPtr tof_sensor_toolbox = ipa_CameraSensors::CreateCameraSensorToolbox();
00154 tof_sensor_toolbox->Init(config_directory_, tof_camera_->GetCameraType(), tof_camera_index_, range_image_size);
00155
00156 cv::Mat intrinsic_mat = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
00157 cv::Mat distortion_map_X = tof_sensor_toolbox->GetDistortionMapX(tof_camera_type_, tof_camera_index_);
00158 cv::Mat distortion_map_Y = tof_sensor_toolbox->GetDistortionMapY(tof_camera_type_, tof_camera_index_);
00159 tof_camera_->SetIntrinsics(intrinsic_mat, distortion_map_X, distortion_map_Y);
00160
00162 camera_info_service_ = node_handle_.advertiseService("set_camera_info", &CobTofCameraNode::setCameraInfo, this);
00163 image_service_ = node_handle_.advertiseService("get_images", &CobTofCameraNode::imageSrvCallback, this);
00164 xyz_image_publisher_ = image_transport_.advertiseCamera("image_xyz", 1);
00165 grey_image_publisher_ = image_transport_.advertiseCamera("image_grey", 1);
00166 if(publish_point_cloud_2_) topicPub_pointCloud2_ = node_handle_.advertise<sensor_msgs::PointCloud2>("point_cloud2", 1);
00167 if(publish_point_cloud_) topicPub_pointCloud_ = node_handle_.advertise<sensor_msgs::PointCloud>("point_cloud", 1);
00168
00169 cv::Mat d = tof_sensor_toolbox->GetDistortionParameters(tof_camera_type_, tof_camera_index_);
00170 camera_info_msg_.header.stamp = ros::Time::now();
00171 camera_info_msg_.header.frame_id = "head_tof_link";
00172
00173
00174
00175
00176
00177
00178 cv::Mat k = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189 camera_info_msg_.width = range_sensor_width;
00190 camera_info_msg_.height = range_sensor_height;
00191
00192 return true;
00193 }
00194
00199 bool setCameraInfo(sensor_msgs::SetCameraInfo::Request& req,
00200 sensor_msgs::SetCameraInfo::Response& rsp)
00201 {
00203 camera_info_msg_ = req.camera_info;
00204
00205 rsp.success = false;
00206 rsp.status_message = "[tof_camera] Setting camera parameters through ROS not implemented";
00207
00208 return true;
00209 }
00210
00212 bool spin()
00213 {
00214 boost::mutex::scoped_lock lock(service_mutex_);
00215 sensor_msgs::Image::Ptr xyz_image_msg_ptr;
00216 sensor_msgs::Image::Ptr grey_image_msg_ptr;
00217 sensor_msgs::CameraInfo tof_image_info;
00218
00219 if(tof_camera_->AcquireImages(0, &grey_image_32F1_, &xyz_image_32F3_, false, false, ipa_CameraSensors::INTENSITY_32F1) & ipa_Utils::RET_FAILED)
00220 {
00221 ROS_ERROR("[tof_camera] Tof image acquisition failed");
00222 return false;
00223 }
00224
00226
00227
00228 if(filter_xyz_tearoff_edges_) ipa_Utils::FilterTearOffEdges(xyz_image_32F3_, 0, (float)tearoff_tear_half_fraction_);
00229 if(filter_xyz_by_amplitude_) ipa_Utils::FilterByAmplitude(xyz_image_32F3_, grey_image_32F1_, 0, 0, lower_amplitude_threshold_, upper_amplitude_threshold_);
00230
00231 try
00232 {
00233 IplImage img = xyz_image_32F3_;
00234 xyz_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img, "passthrough");
00235 }
00236 catch (sensor_msgs::CvBridgeException error)
00237 {
00238 ROS_ERROR("[tof_camera] Could not convert 32bit xyz IplImage to ROS message");
00239 return false;
00240 }
00241
00242 try
00243 {
00244 IplImage img = grey_image_32F1_;
00245 grey_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img, "passthrough");
00246 }
00247 catch (sensor_msgs::CvBridgeException error)
00248 {
00249 ROS_ERROR("[tof_camera] Could not convert 32bit grey IplImage to ROS message");
00250 return false;
00251 }
00252
00254 ros::Time now = ros::Time::now();
00255 xyz_image_msg_ptr->header.stamp = now;
00256 xyz_image_msg_ptr->header.frame_id = "head_tof_link";
00257 grey_image_msg_ptr->header.stamp = now;
00258 grey_image_msg_ptr->header.frame_id = "head_tof_link";
00259
00260 tof_image_info = camera_info_msg_;
00261 tof_image_info.width = grey_image_32F1_.cols;
00262 tof_image_info.height = grey_image_32F1_.rows;
00263 tof_image_info.header.stamp = now;
00264 tof_image_info.header.frame_id = "head_tof_link";
00265
00267 xyz_image_publisher_.publish(*xyz_image_msg_ptr, tof_image_info);
00268 grey_image_publisher_.publish(*grey_image_msg_ptr, tof_image_info);
00269
00270 if(publish_point_cloud_) publishPointCloud(now);
00271 if(publish_point_cloud_2_) publishPointCloud2(now);
00272
00273 return true;
00274 }
00275
00276 void publishPointCloud(ros::Time now)
00277 {
00278 ROS_DEBUG("convert xyz_image to point_cloud");
00279 sensor_msgs::PointCloud pc_msg;
00280
00281 pc_msg.header.stamp = now;
00282 pc_msg.header.frame_id = "head_tof_link";
00283
00284 cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
00285 cv::Mat cpp_grey_image_32F1 = grey_image_32F1_;
00286
00287 float* f_ptr = 0;
00288 for (int row = 0; row < cpp_xyz_image_32F3.rows; row++)
00289 {
00290 f_ptr = cpp_xyz_image_32F3.ptr<float>(row);
00291 for (int col = 0; col < cpp_xyz_image_32F3.cols; col++)
00292 {
00293 geometry_msgs::Point32 pt;
00294 pt.x = f_ptr[3*col + 0];
00295 pt.y = f_ptr[3*col + 1];
00296 pt.z = f_ptr[3*col + 2];
00297 pc_msg.points.push_back(pt);
00298 }
00299 }
00300 topicPub_pointCloud_.publish(pc_msg);
00301 }
00302
00303 void publishPointCloud2(ros::Time now)
00304 {
00305 cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
00306 cv::Mat cpp_confidence_mask_32F1 = grey_image_32F1_;
00307
00308 sensor_msgs::PointCloud2 pc_msg;
00309
00310 pc_msg.header.stamp = now;
00311 pc_msg.header.frame_id = "head_tof_link";
00312 pc_msg.width = cpp_xyz_image_32F3.cols;
00313 pc_msg.height = cpp_xyz_image_32F3.rows;
00314 pc_msg.fields.resize(4);
00315 pc_msg.fields[0].name = "x";
00316 pc_msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
00317 pc_msg.fields[1].name = "y";
00318 pc_msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
00319 pc_msg.fields[2].name = "z";
00320 pc_msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
00321 pc_msg.fields[3].name = "confidence";
00322 pc_msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
00323 int offset = 0;
00324 for (size_t d = 0; d < pc_msg.fields.size(); ++d, offset += 4)
00325 {
00326 pc_msg.fields[d].offset = offset;
00327 }
00328 pc_msg.point_step = 16;
00329 pc_msg.row_step = pc_msg.point_step * pc_msg.width;
00330 pc_msg.data.resize (pc_msg.width*pc_msg.height*pc_msg.point_step);
00331 pc_msg.is_dense = true;
00332 pc_msg.is_bigendian = false;
00333
00334 float* f_ptr = 0;
00335 float* g_ptr = 0;
00336 int pc_msg_idx=0;
00337 for (int row = 0; row < cpp_xyz_image_32F3.rows; row++)
00338 {
00339 f_ptr = cpp_xyz_image_32F3.ptr<float>(row);
00340 g_ptr = cpp_confidence_mask_32F1.ptr<float>(row);
00341 for (int col = 0; col < cpp_xyz_image_32F3.cols; col++, pc_msg_idx++)
00342 {
00343 memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step], &f_ptr[3*col], 3*sizeof(float));
00344 memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step + pc_msg.fields[3].offset], &g_ptr[col], sizeof(float));
00345 }
00346 }
00347 topicPub_pointCloud2_.publish(pc_msg);
00348 }
00349
00350 bool imageSrvCallback(cob_camera_sensors::GetTOFImages::Request &req,
00351 cob_camera_sensors::GetTOFImages::Response &res)
00352 {
00353 boost::mutex::scoped_lock lock(service_mutex_);
00354
00355 try
00356 {
00357 IplImage grey_img = grey_image_32F1_;
00358 IplImage xyz_img = xyz_image_32F3_;
00359 res.greyImage = *(sensor_msgs::CvBridge::cvToImgMsg(&grey_img, "passthrough"));
00360 res.xyzImage = *(sensor_msgs::CvBridge::cvToImgMsg(&xyz_img, "passthrough"));
00361 }
00362 catch (sensor_msgs::CvBridgeException error)
00363 {
00364 ROS_ERROR("[tof_camera_type_node] Could not convert IplImage to ROS message");
00365 }
00366
00367
00368 ros::Time now = ros::Time::now();
00369 res.greyImage.header.stamp = now;
00370 res.greyImage.header.frame_id = "head_tof_link";
00371 res.xyzImage.header.stamp = now;
00372 res.xyzImage.header.frame_id = "head_tof_link";
00373 return true;
00374 }
00375
00376 bool loadParameters()
00377 {
00378 std::string tmp_string = "NULL";
00379
00381 if (node_handle_.getParam("tof_camera/configuration_files", config_directory_) == false)
00382 {
00383 ROS_ERROR("[tof_camera] Path to xml configuration for tof camera not specified");
00384 return false;
00385 }
00386
00387 ROS_INFO("Configuration directory: %s", config_directory_.c_str());
00388
00390 if (node_handle_.getParam("tof_camera/tof_camera_index", tof_camera_index_) == false)
00391 {
00392 ROS_ERROR("[tof_camera] 'tof_camera_index' (0 or 1) not specified");
00393 return false;
00394 }
00395
00397 if (node_handle_.getParam("tof_camera/tof_camera_type", tmp_string) == false)
00398 {
00399 ROS_ERROR("[tof_camera] 'tof_camera_type' not specified");
00400 return false;
00401 }
00402 if (tmp_string == "CAM_SWISSRANGER")
00403 {
00404 tof_camera_ = ipa_CameraSensors::CreateRangeImagingSensor_Swissranger();
00405 tof_camera_type_ = ipa_CameraSensors::CAM_SWISSRANGER;
00406 }
00407 else if (tmp_string == "CAM_VIRTUAL")
00408 {
00409 tof_camera_ = ipa_CameraSensors::CreateRangeImagingSensor_VirtualCam();
00410 tof_camera_type_ = ipa_CameraSensors::CAM_VIRTUALRANGE;
00411 }
00412 else
00413 {
00414 std::string str = "[tof_camera] Camera type '" + tmp_string + "' unknown, try 'CAM_SWISSRANGER'";
00415 ROS_ERROR("%s", str.c_str());
00416 return false;
00417 }
00418
00419 ROS_INFO("Camera type: %s_%d", tmp_string.c_str(), tof_camera_index_);
00420
00422 if (node_handle_.getParam("tof_camera/filter_xyz_by_amplitude", filter_xyz_by_amplitude_) == false)
00423 {
00424 ROS_ERROR("[tof_camera] 'filter_xyz_by_amplitude not specified");
00425 return false;
00426 }
00428 if (node_handle_.getParam("tof_camera/filter_xyz_tearoff_edges", filter_xyz_tearoff_edges_) == false)
00429 {
00430 ROS_ERROR("[tof_camera] 'filter_xyz_tearoff_edges_' not specified");
00431 return false;
00432 }
00434 if (node_handle_.getParam("tof_camera/lower_amplitude_threshold", lower_amplitude_threshold_) == false)
00435 {
00436 ROS_ERROR("[tof_camera] 'lower_amplitude_threshold' not specified");
00437 return false;
00438 }
00440 if (node_handle_.getParam("tof_camera/upper_amplitude_threshold", upper_amplitude_threshold_) == false)
00441 {
00442 ROS_ERROR("[tof_camera] 'upper_amplitude_threshold' not specified");
00443 return false;
00444 }
00446 if (node_handle_.getParam("tof_camera/tearoff_pi_half_fraction", tearoff_tear_half_fraction_) == false)
00447 {
00448 ROS_ERROR("[tof_camera] 'tearoff_pi_half_fraction' not specified");
00449 return false;
00450 }
00452 if (node_handle_.getParam("tof_camera/ros_node_mode", tmp_string) == false)
00453 {
00454 ROS_ERROR("[tof_camera] Mode for tof camera node not specified");
00455 return false;
00456 }
00457 if (tmp_string == "MODE_SERVICE")
00458 {
00459 ros_node_mode_ = CobTofCameraNode::MODE_SERVICE;
00460 }
00461 else if (tmp_string == "MODE_TOPIC")
00462 {
00463 ros_node_mode_ = CobTofCameraNode::MODE_TOPIC;
00464 }
00465 else
00466 {
00467 std::string str = "[tof_camera] Mode '" + tmp_string + "' unknown, try 'MODE_SERVICE' or 'MODE_TOPIC'";
00468 ROS_ERROR("%s", str.c_str());
00469 return false;
00470 }
00471
00472 if(node_handle_.getParam("tof_camera/publish_point_cloud", publish_point_cloud_) == false)
00473 {
00474 ROS_WARN("[tof_camera] Flag for publishing PointCloud not set, falling back to default (false)");
00475 }
00476 if(node_handle_.getParam("tof_camera/publish_point_cloud_2", publish_point_cloud_2_) == false)
00477 {
00478 ROS_WARN("[tof_camera] Flag for publishing PointCloud2 not set, falling back to default (false)");
00479 }
00480
00481
00482 ROS_INFO("ROS node mode: %s", tmp_string.c_str());
00483
00484 return true;
00485 }
00486 };
00487
00488
00489
00490
00491 int main(int argc, char** argv)
00492 {
00494 ros::init(argc, argv, "tof_camera");
00495
00497 ros::NodeHandle nh;
00498
00500 CobTofCameraNode camera_node(nh);
00501
00503 if (!camera_node.init()) return 0;
00504
00505
00506 ros::Rate rate(100);
00507 while(nh.ok())
00508 {
00509 camera_node.spin();
00510 ros::spinOnce();
00511 rate.sleep();
00512 }
00513
00514 return 0;
00515 }