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
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055
00056 #include <cob_image_flip/kinect_image_flip.h>
00057
00058 namespace cob_image_flip
00059 {
00060 CobKinectImageFlip::CobKinectImageFlip(ros::NodeHandle nh)
00061 {
00062 node_handle_ = nh;
00063
00064
00065 std::string robot;
00066 flip_color_image_ = false;
00067 flip_pointcloud_ = false;
00068 pointcloud_data_format_ = "xyz";
00069
00070 img_sub_counter_ = 0;
00071 pc_sub_counter_ = 0;
00072
00073 std::cout << "\n--------------------------\nKinect Image Flip Parameters:\n--------------------------" << std::endl;
00074 node_handle_.param("flip_color_image", flip_color_image_, false);
00075 std::cout << "flip_color_image = " << flip_color_image_ << std::endl;
00076 node_handle_.param("rotation", rotation_, 180);
00077 std::cout << "rotation = " << rotation_ << std::endl;
00078 node_handle_.param("flip_pointcloud", flip_pointcloud_, false);
00079 std::cout << "flip_pointcloud = " << flip_pointcloud_ << std::endl;
00080 node_handle_.param<std::string>("pointcloud_data_format", pointcloud_data_format_, "xyz");
00081 std::cout << "pointcloud_data_format = " << pointcloud_data_format_ << std::endl;
00082 node_handle_.param("display_warnings", display_warnings_, false);
00083 std::cout << "display_warnings = " << display_warnings_ << std::endl;
00084 node_handle_.param("display_timing", display_timing_, false);
00085 std::cout << "display_timing = " << display_timing_ << std::endl;
00086 node_handle_.param<std::string>("robot", robot, "cob3-3");
00087 std::cout << "robot = " << robot << std::endl;
00088
00089
00090 cob3Number_ = 0;
00091
00092 std::stringstream ss;
00093 ss << robot.substr(robot.find("cob3-")+5);
00094 ss >> cob3Number_;
00095 std::cout << "CobKinectImageFlip: Robot number is cob3-" << cob3Number_ << "." << std::endl;
00096
00097
00098
00099 transform_listener_ = 0;
00100
00101
00102
00103 if (flip_color_image_ == true)
00104 {
00105 it_ = new image_transport::ImageTransport(node_handle_);
00106
00107
00108
00109
00110
00111
00112 color_camera_image_sub_.registerCallback(boost::bind(&CobKinectImageFlip::imageCallback, this, _1));
00113
00114
00115
00116 color_camera_image_pub_ = it_->advertise("colorimage_out", 1, boost::bind(&CobKinectImageFlip::imgConnectCB, this, _1), boost::bind(&CobKinectImageFlip::imgDisconnectCB, this, _1));
00117 }
00118 else
00119 {
00120 it_ = 0;
00121 }
00122
00123
00124
00125
00126 if (flip_pointcloud_ == true)
00127 {
00128 point_cloud_pub_ = node_handle_.advertise<sensor_msgs::PointCloud2>("pointcloud_out", 1, boost::bind(&CobKinectImageFlip::pcConnectCB, this, _1), boost::bind(&CobKinectImageFlip::pcDisconnectCB, this, _1));
00129 }
00130
00131
00132
00133 transform_listener_ = new tf::TransformListener(node_handle_);
00134
00135 std::cout << "CobKinectImageFlip initilized." << std::endl;
00136 }
00137
00138 CobKinectImageFlip::~CobKinectImageFlip()
00139 {
00140 if (it_ != 0)
00141 delete it_;
00142
00143
00144 if (transform_listener_ != 0)
00145 delete transform_listener_;
00146 }
00147
00148 unsigned long CobKinectImageFlip::init()
00149 {
00150
00151
00152
00153
00154
00155
00156 return ipa_Utils::RET_OK;
00157 }
00158
00159 unsigned long CobKinectImageFlip::convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image)
00160 {
00161 try
00162 {
00163 color_image_ptr = cv_bridge::toCvShare(color_image_msg, sensor_msgs::image_encodings::BGR8);
00164 } catch (cv_bridge::Exception& e)
00165 {
00166 ROS_ERROR("PeopleDetection: cv_bridge exception: %s", e.what());
00167 return ipa_Utils::RET_FAILED;
00168 }
00169 color_image = color_image_ptr->image;
00170
00171 return ipa_Utils::RET_OK;
00172 }
00173
00174 template <typename T>
00175 void CobKinectImageFlip::inputCallback(const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg)
00176 {
00177
00178
00179
00180
00181 bool turnAround = false;
00182 tf::StampedTransform transform;
00183 try
00184 {
00185 transform_listener_->lookupTransform("/base_link", "/head_cam3d_link", ros::Time(0), transform);
00186 tfScalar roll, pitch, yaw;
00187 transform.getBasis().getRPY(roll, pitch, yaw, 1);
00188 if (cob3Number_ == 2)
00189 roll *= -1.;
00190 if (roll > 0.0)
00191 turnAround = true;
00192
00193
00194
00195 } catch (tf::TransformException ex)
00196 {
00197 if (display_warnings_ == true)
00198 ROS_WARN("%s",ex.what());
00199 }
00200
00201 if (turnAround == false)
00202 {
00203
00204
00205
00206
00207
00208 point_cloud_pub_.publish(point_cloud_msg);
00209 }
00210 else
00211 {
00212
00213
00214 pcl::PointCloud<T> point_cloud_src;
00215 pcl::fromROSMsg(*point_cloud_msg, point_cloud_src);
00216
00217 boost::shared_ptr<pcl::PointCloud<T> > point_cloud_turned(new pcl::PointCloud<T>);
00218
00219 point_cloud_turned->header = pcl_conversions::toPCL(point_cloud_msg->header);
00220 point_cloud_turned->height = point_cloud_msg->height;
00221 point_cloud_turned->width = point_cloud_msg->width;
00222
00223
00224 point_cloud_turned->is_dense = true;
00225 point_cloud_turned->resize(point_cloud_src.height*point_cloud_src.width);
00226 for (int v = (int)point_cloud_src.height - 1; v >= 0; v--)
00227 {
00228 for (int u = (int)point_cloud_src.width - 1; u >= 0; u--)
00229 {
00230 (*point_cloud_turned)(point_cloud_src.width-1 - u, point_cloud_src.height-1 - v) = point_cloud_src(u, v);
00231 }
00232 }
00233
00234
00235 sensor_msgs::PointCloud2::Ptr point_cloud_turned_msg(new sensor_msgs::PointCloud2);
00236 pcl::toROSMsg(*point_cloud_turned, *point_cloud_turned_msg);
00237
00238 point_cloud_pub_.publish(point_cloud_turned_msg);
00239
00240
00241
00242
00243 }
00244
00245 if (display_timing_ == true)
00246 ROS_INFO("%d ImageFlip: Time stamp of pointcloud message: %f. Delay: %f.", point_cloud_msg->header.seq, point_cloud_msg->header.stamp.toSec(), ros::Time::now().toSec()-point_cloud_msg->header.stamp.toSec());
00247
00248 }
00249
00250 void CobKinectImageFlip::imageCallback(const sensor_msgs::ImageConstPtr& color_image_msg)
00251 {
00252
00253
00254
00255
00256 if (rotation_==90)
00257 {
00258
00259 cv_bridge::CvImageConstPtr color_image_ptr;
00260 cv::Mat color_image;
00261 convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);
00262
00263
00264 cv::Mat color_image_turned(color_image.cols, color_image.rows, color_image.type());
00265 if (color_image.type() != CV_8UC3)
00266 {
00267 std::cout << "CobKinectImageFlipNodelet::inputCallback: Error: The image format of the color image is not CV_8UC3.\n";
00268 return;
00269 }
00270 for (int v = 0; v < color_image_turned.rows; v++)
00271 {
00272 for (int u = 0; u < color_image_turned.cols; u++)
00273 {
00274 color_image_turned.at<cv::Vec3b>(v,u) = color_image.at<cv::Vec3b>(color_image.rows-1-u,v);
00275 }
00276 }
00277
00278
00279 cv_bridge::CvImage cv_ptr;
00280 cv_ptr.image = color_image_turned;
00281 cv_ptr.encoding = "bgr8";
00282 sensor_msgs::Image::Ptr color_image_turned_msg = cv_ptr.toImageMsg();
00283 color_image_turned_msg->header = color_image_msg->header;
00284 color_camera_image_pub_.publish(color_image_turned_msg);
00285
00286 return;
00287 }
00288 else if (rotation_==270)
00289 {
00290
00291 cv_bridge::CvImageConstPtr color_image_ptr;
00292 cv::Mat color_image;
00293 convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);
00294
00295
00296 cv::Mat color_image_turned(color_image.cols, color_image.rows, color_image.type());
00297 if (color_image.type() != CV_8UC3)
00298 {
00299 std::cout << "CobKinectImageFlipNodelet::inputCallback: Error: The image format of the color image is not CV_8UC3.\n";
00300 return;
00301 }
00302 for (int v = 0; v < color_image_turned.rows; v++)
00303 {
00304 for (int u = 0; u < color_image_turned.cols; u++)
00305 {
00306 color_image_turned.at<cv::Vec3b>(v,u) = color_image.at<cv::Vec3b>(u,color_image.cols-1-v);
00307 }
00308 }
00309
00310
00311 cv_bridge::CvImage cv_ptr;
00312 cv_ptr.image = color_image_turned;
00313 cv_ptr.encoding = "bgr8";
00314 sensor_msgs::Image::Ptr color_image_turned_msg = cv_ptr.toImageMsg();
00315 color_image_turned_msg->header = color_image_msg->header;
00316 color_camera_image_pub_.publish(color_image_turned_msg);
00317
00318 return;
00319 }
00320 else if (rotation_==180)
00321 {
00322
00323
00324
00325 cv_bridge::CvImageConstPtr color_image_ptr;
00326 cv::Mat color_image;
00327 convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);
00328
00329
00330 cv::Mat color_image_turned(color_image.rows, color_image.cols, color_image.type());
00331 if (color_image.type() != CV_8UC3)
00332 {
00333 std::cout << "CobKinectImageFlipNodelet::inputCallback: Error: The image format of the color image is not CV_8UC3.\n";
00334 return;
00335 }
00336 for (int v = 0; v < color_image.rows; v++)
00337 {
00338 uchar* src = color_image.ptr(v);
00339 uchar* dst = color_image_turned.ptr(color_image.rows - v - 1);
00340 dst += 3 * (color_image.cols - 1);
00341 for (int u = 0; u < color_image.cols; u++)
00342 {
00343 for (int k = 0; k < 3; k++)
00344 {
00345 *dst = *src;
00346 src++;
00347 dst++;
00348 }
00349 dst -= 6;
00350 }
00351 }
00352
00353
00354 cv_bridge::CvImage cv_ptr;
00355 cv_ptr.image = color_image_turned;
00356 cv_ptr.encoding = "bgr8";
00357 sensor_msgs::Image::Ptr color_image_turned_msg = cv_ptr.toImageMsg();
00358 color_image_turned_msg->header = color_image_msg->header;
00359 color_camera_image_pub_.publish(color_image_turned_msg);
00360
00361 return;
00362 }
00363
00364
00365 bool turnAround = false;
00366 tf::StampedTransform transform;
00367 try
00368 {
00369 transform_listener_->lookupTransform("/base_link", "/head_cam3d_link", ros::Time(0), transform);
00370 tfScalar roll, pitch, yaw;
00371 transform.getBasis().getRPY(roll, pitch, yaw, 1);
00372 if (cob3Number_ == 2)
00373 roll *= -1.;
00374 if (roll > 0.0)
00375 turnAround = true;
00376
00377
00378
00379 } catch (tf::TransformException ex)
00380 {
00381 if (display_warnings_ == true)
00382 ROS_WARN("%s",ex.what());
00383 }
00384
00385
00386 if (turnAround == false)
00387 {
00388
00389 sensor_msgs::Image color_image_turned_msg = *color_image_msg;
00390 color_camera_image_pub_.publish(color_image_turned_msg);
00391 }
00392 else
00393 {
00394
00395 cv_bridge::CvImageConstPtr color_image_ptr;
00396 cv::Mat color_image;
00397 convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image);
00398
00399
00400 cv::Mat color_image_turned(color_image.rows, color_image.cols, color_image.type());
00401 if (color_image.type() != CV_8UC3)
00402 {
00403 std::cout << "CobKinectImageFlipNodelet::inputCallback: Error: The image format of the color image is not CV_8UC3.\n";
00404 return;
00405 }
00406 for (int v = 0; v < color_image.rows; v++)
00407 {
00408 uchar* src = color_image.ptr(v);
00409 uchar* dst = color_image_turned.ptr(color_image.rows - v - 1);
00410 dst += 3 * (color_image.cols - 1);
00411 for (int u = 0; u < color_image.cols; u++)
00412 {
00413 for (int k = 0; k < 3; k++)
00414 {
00415 *dst = *src;
00416 src++;
00417 dst++;
00418 }
00419 dst -= 6;
00420 }
00421 }
00422 cv_bridge::CvImage cv_ptr;
00423 cv_ptr.image = color_image_turned;
00424 cv_ptr.encoding = "bgr8";
00425 sensor_msgs::Image::Ptr color_image_turned_msg = cv_ptr.toImageMsg();
00426 color_image_turned_msg->header = color_image_msg->header;
00427 color_camera_image_pub_.publish(color_image_turned_msg);
00428 }
00429
00430
00431 }
00432
00433 void CobKinectImageFlip::imgConnectCB(const image_transport::SingleSubscriberPublisher& pub)
00434 {
00435 img_sub_counter_++;
00436 if(img_sub_counter_ == 1)
00437 {
00438 ROS_DEBUG("connecting");
00439 color_camera_image_sub_.subscribe(*it_, "colorimage_in", 1);
00440 }
00441 }
00442
00443 void CobKinectImageFlip::imgDisconnectCB(const image_transport::SingleSubscriberPublisher& pub)
00444 {
00445 img_sub_counter_--;
00446 if(img_sub_counter_ == 0)
00447 {
00448 ROS_DEBUG("disconnecting");
00449 color_camera_image_sub_.unsubscribe();
00450 }
00451 }
00452
00453 void CobKinectImageFlip::pcConnectCB(const ros::SingleSubscriberPublisher& pub)
00454 {
00455 pc_sub_counter_++;
00456 if(pc_sub_counter_ == 1)
00457 {
00458 ROS_DEBUG("connecting");
00459 if (pointcloud_data_format_.compare("xyz") == 0)
00460 point_cloud_sub_ = node_handle_.subscribe<sensor_msgs::PointCloud2>("pointcloud_in", 1, &CobKinectImageFlip::inputCallback<pcl::PointXYZ>, this);
00461 else if (pointcloud_data_format_.compare("xyzrgb") == 0)
00462 point_cloud_sub_ = node_handle_.subscribe<sensor_msgs::PointCloud2>("pointcloud_in", 1, &CobKinectImageFlip::inputCallback<pcl::PointXYZRGB>, this);
00463 else
00464 {
00465 ROS_ERROR("Unknown pointcloud format specified in the paramter file.");
00466 pc_sub_counter_ = 0;
00467 }
00468 }
00469 }
00470
00471 void CobKinectImageFlip::pcDisconnectCB(const ros::SingleSubscriberPublisher& pub)
00472 {
00473 pc_sub_counter_--;
00474 if(pc_sub_counter_ == 0)
00475 {
00476 ROS_DEBUG("disconnecting");
00477 point_cloud_sub_.shutdown();
00478 }
00479 }
00480
00481 }