27 #include <cv_bridge/CvBridge.h> 30 #include <sensor_msgs/Image.h> 31 #include <sensor_msgs/CameraInfo.h> 33 #include <sensor_msgs/SetCameraInfo.h> 34 #include <sensor_msgs/PointCloud.h> 35 #include <sensor_msgs/PointCloud2.h> 37 #include <cob_camera_sensors/GetTOFImages.h> 45 #include <boost/thread/mutex.hpp> 94 : node_handle_(node_handle),
95 image_transport_(node_handle),
97 xyz_image_32F3_(cv::Mat()),
98 grey_image_32F1_(cv::Mat()),
99 publish_point_cloud_(false),
100 publish_point_cloud_2_(false)
108 tof_camera_->Close();
115 if (loadParameters() ==
false)
117 ROS_ERROR(
"[color_camera] Could not read all parameters from launch file");
125 std::stringstream ss;
126 ss <<
"Initialization of tof camera ";
127 ss << tof_camera_index_;
129 ROS_ERROR(
"[tof_camera] %s", ss.str().c_str());
136 std::stringstream ss;
137 ss <<
"Could not open tof camera ";
138 ss << tof_camera_index_;
139 ROS_ERROR(
"[tof_camera] %s", ss.str().c_str());
147 tof_camera_->GetProperty(&cameraProperty);
150 cv::Size range_image_size(range_sensor_width, range_sensor_height);
154 tof_sensor_toolbox->Init(config_directory_, tof_camera_->GetCameraType(), tof_camera_index_, range_image_size);
156 cv::Mat intrinsic_mat = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
157 cv::Mat distortion_map_X = tof_sensor_toolbox->GetDistortionMapX(tof_camera_type_, tof_camera_index_);
158 cv::Mat distortion_map_Y = tof_sensor_toolbox->GetDistortionMapY(tof_camera_type_, tof_camera_index_);
159 tof_camera_->SetIntrinsics(intrinsic_mat, distortion_map_X, distortion_map_Y);
164 xyz_image_publisher_ = image_transport_.
advertiseCamera(
"image_xyz", 1);
165 grey_image_publisher_ = image_transport_.
advertiseCamera(
"image_grey", 1);
166 if(publish_point_cloud_2_) topicPub_pointCloud2_ = node_handle_.
advertise<sensor_msgs::PointCloud2>(
"point_cloud2", 1);
167 if(publish_point_cloud_) topicPub_pointCloud_ = node_handle_.
advertise<sensor_msgs::PointCloud>(
"point_cloud", 1);
169 cv::Mat
d = tof_sensor_toolbox->GetDistortionParameters(tof_camera_type_, tof_camera_index_);
171 camera_info_msg_.header.frame_id =
"head_tof_link";
178 cv::Mat k = tof_sensor_toolbox->GetIntrinsicMatrix(tof_camera_type_, tof_camera_index_);
189 camera_info_msg_.width = range_sensor_width;
190 camera_info_msg_.height = range_sensor_height;
200 sensor_msgs::SetCameraInfo::Response& rsp)
203 camera_info_msg_ = req.camera_info;
206 rsp.status_message =
"[tof_camera] Setting camera parameters through ROS not implemented";
214 boost::mutex::scoped_lock lock(service_mutex_);
215 sensor_msgs::Image::Ptr xyz_image_msg_ptr;
216 sensor_msgs::Image::Ptr grey_image_msg_ptr;
217 sensor_msgs::CameraInfo tof_image_info;
219 if(tof_camera_->AcquireImages(0, &grey_image_32F1_, &xyz_image_32F3_,
false,
false, ipa_CameraSensors::INTENSITY_32F1) &
ipa_Utils::RET_FAILED)
221 ROS_ERROR(
"[tof_camera] Tof image acquisition failed");
229 if(filter_xyz_by_amplitude_)
ipa_Utils::FilterByAmplitude(xyz_image_32F3_, grey_image_32F1_, 0, 0, lower_amplitude_threshold_, upper_amplitude_threshold_);
233 IplImage img = xyz_image_32F3_;
234 xyz_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img,
"passthrough");
236 catch (sensor_msgs::CvBridgeException error)
238 ROS_ERROR(
"[tof_camera] Could not convert 32bit xyz IplImage to ROS message");
244 IplImage img = grey_image_32F1_;
245 grey_image_msg_ptr = sensor_msgs::CvBridge::cvToImgMsg(&img,
"passthrough");
247 catch (sensor_msgs::CvBridgeException error)
249 ROS_ERROR(
"[tof_camera] Could not convert 32bit grey IplImage to ROS message");
255 xyz_image_msg_ptr->header.stamp = now;
256 xyz_image_msg_ptr->header.frame_id =
"head_tof_link";
257 grey_image_msg_ptr->header.stamp = now;
258 grey_image_msg_ptr->header.frame_id =
"head_tof_link";
260 tof_image_info = camera_info_msg_;
261 tof_image_info.width = grey_image_32F1_.cols;
262 tof_image_info.height = grey_image_32F1_.rows;
263 tof_image_info.header.stamp = now;
264 tof_image_info.header.frame_id =
"head_tof_link";
267 xyz_image_publisher_.
publish(*xyz_image_msg_ptr, tof_image_info);
268 grey_image_publisher_.
publish(*grey_image_msg_ptr, tof_image_info);
270 if(publish_point_cloud_) publishPointCloud(now);
271 if(publish_point_cloud_2_) publishPointCloud2(now);
278 ROS_DEBUG(
"convert xyz_image to point_cloud");
279 sensor_msgs::PointCloud pc_msg;
281 pc_msg.header.stamp = now;
282 pc_msg.header.frame_id =
"head_tof_link";
284 cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
285 cv::Mat cpp_grey_image_32F1 = grey_image_32F1_;
288 for (
int row = 0; row < cpp_xyz_image_32F3.rows; row++)
290 f_ptr = cpp_xyz_image_32F3.ptr<
float>(row);
291 for (
int col = 0; col < cpp_xyz_image_32F3.cols; col++)
293 geometry_msgs::Point32 pt;
294 pt.x = f_ptr[3*col + 0];
295 pt.y = f_ptr[3*col + 1];
296 pt.z = f_ptr[3*col + 2];
297 pc_msg.points.push_back(pt);
300 topicPub_pointCloud_.
publish(pc_msg);
305 cv::Mat cpp_xyz_image_32F3 = xyz_image_32F3_;
306 cv::Mat cpp_confidence_mask_32F1 = grey_image_32F1_;
308 sensor_msgs::PointCloud2 pc_msg;
310 pc_msg.header.stamp = now;
311 pc_msg.header.frame_id =
"head_tof_link";
312 pc_msg.width = cpp_xyz_image_32F3.cols;
313 pc_msg.height = cpp_xyz_image_32F3.rows;
314 pc_msg.fields.resize(4);
315 pc_msg.fields[0].name =
"x";
316 pc_msg.fields[0].datatype = sensor_msgs::PointField::FLOAT32;
317 pc_msg.fields[1].name =
"y";
318 pc_msg.fields[1].datatype = sensor_msgs::PointField::FLOAT32;
319 pc_msg.fields[2].name =
"z";
320 pc_msg.fields[2].datatype = sensor_msgs::PointField::FLOAT32;
321 pc_msg.fields[3].name =
"confidence";
322 pc_msg.fields[3].datatype = sensor_msgs::PointField::FLOAT32;
324 for (
size_t d = 0;
d < pc_msg.fields.size(); ++
d, offset += 4)
326 pc_msg.fields[
d].offset = offset;
328 pc_msg.point_step = 16;
329 pc_msg.row_step = pc_msg.point_step * pc_msg.width;
330 pc_msg.data.resize (pc_msg.width*pc_msg.height*pc_msg.point_step);
331 pc_msg.is_dense =
true;
332 pc_msg.is_bigendian =
false;
337 for (
int row = 0; row < cpp_xyz_image_32F3.rows; row++)
339 f_ptr = cpp_xyz_image_32F3.ptr<
float>(row);
340 g_ptr = cpp_confidence_mask_32F1.ptr<
float>(row);
341 for (
int col = 0; col < cpp_xyz_image_32F3.cols; col++, pc_msg_idx++)
343 memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step], &f_ptr[3*col], 3*
sizeof(
float));
344 memcpy(&pc_msg.data[pc_msg_idx * pc_msg.point_step + pc_msg.fields[3].offset], &g_ptr[col],
sizeof(
float));
347 topicPub_pointCloud2_.
publish(pc_msg);
351 cob_camera_sensors::GetTOFImages::Response &res)
353 boost::mutex::scoped_lock lock(service_mutex_);
357 IplImage grey_img = grey_image_32F1_;
358 IplImage xyz_img = xyz_image_32F3_;
359 res.greyImage = *(sensor_msgs::CvBridge::cvToImgMsg(&grey_img,
"passthrough"));
360 res.xyzImage = *(sensor_msgs::CvBridge::cvToImgMsg(&xyz_img,
"passthrough"));
362 catch (sensor_msgs::CvBridgeException error)
364 ROS_ERROR(
"[tof_camera_type_node] Could not convert IplImage to ROS message");
369 res.greyImage.header.stamp = now;
370 res.greyImage.header.frame_id =
"head_tof_link";
371 res.xyzImage.header.stamp = now;
372 res.xyzImage.header.frame_id =
"head_tof_link";
378 std::string tmp_string =
"NULL";
381 if (node_handle_.
getParam(
"tof_camera/configuration_files", config_directory_) ==
false)
383 ROS_ERROR(
"[tof_camera] Path to xml configuration for tof camera not specified");
387 ROS_INFO(
"Configuration directory: %s", config_directory_.c_str());
390 if (node_handle_.
getParam(
"tof_camera/tof_camera_index", tof_camera_index_) ==
false)
392 ROS_ERROR(
"[tof_camera] 'tof_camera_index' (0 or 1) not specified");
397 if (node_handle_.
getParam(
"tof_camera/tof_camera_type", tmp_string) ==
false)
399 ROS_ERROR(
"[tof_camera] 'tof_camera_type' not specified");
402 if (tmp_string ==
"CAM_SWISSRANGER")
407 else if (tmp_string ==
"CAM_VIRTUAL")
414 std::string str =
"[tof_camera] Camera type '" + tmp_string +
"' unknown, try 'CAM_SWISSRANGER'";
419 ROS_INFO(
"Camera type: %s_%d", tmp_string.c_str(), tof_camera_index_);
422 if (node_handle_.
getParam(
"tof_camera/filter_xyz_by_amplitude", filter_xyz_by_amplitude_) ==
false)
424 ROS_ERROR(
"[tof_camera] 'filter_xyz_by_amplitude not specified");
428 if (node_handle_.
getParam(
"tof_camera/filter_xyz_tearoff_edges", filter_xyz_tearoff_edges_) ==
false)
430 ROS_ERROR(
"[tof_camera] 'filter_xyz_tearoff_edges_' not specified");
434 if (node_handle_.
getParam(
"tof_camera/lower_amplitude_threshold", lower_amplitude_threshold_) ==
false)
436 ROS_ERROR(
"[tof_camera] 'lower_amplitude_threshold' not specified");
440 if (node_handle_.
getParam(
"tof_camera/upper_amplitude_threshold", upper_amplitude_threshold_) ==
false)
442 ROS_ERROR(
"[tof_camera] 'upper_amplitude_threshold' not specified");
446 if (node_handle_.
getParam(
"tof_camera/tearoff_pi_half_fraction", tearoff_tear_half_fraction_) ==
false)
448 ROS_ERROR(
"[tof_camera] 'tearoff_pi_half_fraction' not specified");
452 if (node_handle_.
getParam(
"tof_camera/ros_node_mode", tmp_string) ==
false)
454 ROS_ERROR(
"[tof_camera] Mode for tof camera node not specified");
457 if (tmp_string ==
"MODE_SERVICE")
461 else if (tmp_string ==
"MODE_TOPIC")
467 std::string str =
"[tof_camera] Mode '" + tmp_string +
"' unknown, try 'MODE_SERVICE' or 'MODE_TOPIC'";
472 if(node_handle_.
getParam(
"tof_camera/publish_point_cloud", publish_point_cloud_) ==
false)
474 ROS_WARN(
"[tof_camera] Flag for publishing PointCloud not set, falling back to default (false)");
476 if(node_handle_.
getParam(
"tof_camera/publish_point_cloud_2", publish_point_cloud_2_) ==
false)
478 ROS_WARN(
"[tof_camera] Flag for publishing PointCloud2 not set, falling back to default (false)");
482 ROS_INFO(
"ROS node mode: %s", tmp_string.c_str());
491 int main(
int argc,
char** argv)
503 if (!camera_node.
init())
return 0;
ros::NodeHandle node_handle_
Node handle.
ros::Publisher topicPub_pointCloud2_
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
boost::mutex service_mutex_
void publishPointCloud(ros::Time now)
void publish(const boost::shared_ptr< M > &message) const
t_cameraResolution cameraResolution
CobTofCameraNode(const ros::NodeHandle &node_handle)
Constructor.
bool filter_xyz_by_amplitude_
bool setCameraInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
__DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_VirtualCam()
ipa_CameraSensors::t_cameraType tof_camera_type_
Type of tof camera.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
__DLL_LIBCAMERASENSORS__ CameraSensorToolboxPtr CreateCameraSensorToolbox()
int lower_amplitude_threshold_
int tof_camera_index_
Camera index of the color camera for IPA configuration file.
ros::Publisher topicPub_pointCloud_
double tearoff_tear_half_fraction_
bool publish_point_cloud_2_
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
bool publish_point_cloud_
image_transport::CameraPublisher xyz_image_publisher_
Publishes xyz image data.
boost::shared_ptr< AbstractRangeImagingSensor > AbstractRangeImagingSensorPtr
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer camera_info_service_
Service to set/modify camera parameters.
cv::Mat grey_image_32F1_
OpenCV image holding the point cloud.
bool imageSrvCallback(cob_camera_sensors::GetTOFImages::Request &req, cob_camera_sensors::GetTOFImages::Response &res)
bool filter_xyz_tearoff_edges_
t_cameraPropertyID propertyID
bool getParam(const std::string &key, std::string &s) const
unsigned long FilterTearOffEdges(cv::Mat &xyzImage, cv::Mat *mask, float piHalfFraction=6)
std::string config_directory_
Directory of related IPA configuration file.
__DLL_LIBCAMERASENSORS__ AbstractRangeImagingSensorPtr CreateRangeImagingSensor_Swissranger()
int upper_amplitude_threshold_
unsigned long FilterByAmplitude(cv::Mat &xyzImage, const cv::Mat &greyImage, cv::Mat *mask, cv::Mat *maskColor, float minMaskThresh, float maxMaskThresh)
ROSCPP_DECL void spinOnce()
bool spin()
Continuously advertises xyz and grey images.
sensor_msgs::CameraInfo camera_info_msg_
ROS camera information message (e.g. holding intrinsic parameters)
~CobTofCameraNode()
Destructor.
int main(int argc, char **argv)
image_transport::CameraPublisher grey_image_publisher_
Publishes grey image data.
image_transport::ImageTransport image_transport_
Image transport instance.
CobTofCameraNode::t_Mode ros_node_mode_
OpenCV image holding the amplitude values.
AbstractRangeImagingSensorPtr tof_camera_
Time-of-flight camera instance.
ros::ServiceServer image_service_
void publishPointCloud2(ros::Time now)