$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2010 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_driver 00012 * ROS package name: cob_camera_sensors 00013 * 00014 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00015 * 00016 * Author: Richard Bormann, email:richard.bormann@ipa.fhg.de 00017 * Supervised by: Richard Bormann, email:richard.bormann@ipa.fhg.de 00018 * 00019 * Date of creation: May 2011 00020 * ToDo: 00021 * 00022 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00023 * 00024 * Redistribution and use in source and binary forms, with or without 00025 * modification, are permitted provided that the following conditions are met: 00026 * 00027 * * Redistributions of source code must retain the above copyright 00028 * notice, this list of conditions and the following disclaimer. 00029 * * Redistributions in binary form must reproduce the above copyright 00030 * notice, this list of conditions and the following disclaimer in the 00031 * documentation and/or other materials provided with the distribution. 00032 * * Neither the name of the Fraunhofer Institute for Manufacturing 00033 * Engineering and Automation (IPA) nor the names of its 00034 * contributors may be used to endorse or promote products derived from 00035 * this software without specific prior written permission. 00036 * 00037 * This program is free software: you can redistribute it and/or modify 00038 * it under the terms of the GNU Lesser General Public License LGPL as 00039 * published by the Free Software Foundation, either version 3 of the 00040 * License, or (at your option) any later version. 00041 * 00042 * This program is distributed in the hope that it will be useful, 00043 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00044 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00045 * GNU Lesser General Public License LGPL for more details. 00046 * 00047 * You should have received a copy of the GNU Lesser General Public 00048 * License LGPL along with this program. 00049 * If not, see <http://www.gnu.org/licenses/>. 00050 * 00051 ****************************************************************/ 00052 00053 //################## 00054 //#### includes #### 00055 00056 // ROS includes 00057 #include <ros/ros.h> 00058 #include <nodelet/nodelet.h> 00059 00060 // ROS message includes 00061 #include <sensor_msgs/Image.h> 00062 #include <sensor_msgs/PointCloud2.h> 00063 #include <tf/transform_listener.h> 00064 00065 // topics 00066 #include <message_filters/subscriber.h> 00067 #include <message_filters/synchronizer.h> 00068 #include <message_filters/sync_policies/approximate_time.h> 00069 #include <image_transport/image_transport.h> 00070 #include <image_transport/subscriber_filter.h> 00071 00072 // opencv 00073 #include <opencv/cv.h> 00074 #include <opencv/highgui.h> 00075 #include <cv_bridge/cv_bridge.h> 00076 #include <sensor_msgs/image_encodings.h> 00077 00078 // point cloud 00079 #include <pcl/point_types.h> 00080 #include <pcl_ros/point_cloud.h> 00081 00082 // Plugins 00083 #include <pluginlib/class_list_macros.h> 00084 00085 // System 00086 #include <iostream> 00087 00088 #include <cob_vision_utils/GlobalDefines.h> 00089 00090 00091 namespace ipa_CameraSensors 00092 { 00093 class CobKinectImageFlipNodelet : public nodelet::Nodelet 00094 { 00095 protected: 00096 message_filters::Subscriber<sensor_msgs::PointCloud2> point_cloud_sub_; 00097 ros::Publisher point_cloud_pub_; 00098 image_transport::ImageTransport* it_; 00099 image_transport::SubscriberFilter color_camera_image_sub_; 00100 image_transport::Publisher color_camera_image_pub_; 00101 message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >* sync_pointcloud_; 00102 message_filters::Connection sync_pointcloud_callback_connection_; 00103 00104 tf::TransformListener* transform_listener_; 00105 00106 ros::NodeHandle node_handle_; 00107 00108 public: 00109 00110 CobKinectImageFlipNodelet() 00111 { 00112 it_ = 0; 00113 sync_pointcloud_ = 0; 00114 transform_listener_ = 0; 00115 } 00116 00117 ~CobKinectImageFlipNodelet() 00118 { 00119 if (it_ != 0) delete it_; 00120 if (sync_pointcloud_ != 0) delete sync_pointcloud_; 00121 if (transform_listener_ != 0) delete transform_listener_; 00122 } 00123 00124 void onInit() 00125 { 00126 node_handle_ = getNodeHandle(); 00127 it_ = new image_transport::ImageTransport(node_handle_); 00128 sync_pointcloud_ = new message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::Image> >(3);//(2); //this parameter is the queue size for comparing time stanps of messages (might work badly if set to 1) 00129 color_camera_image_pub_ = it_->advertise("rgb/upright/image_color", 1); 00130 point_cloud_pub_ = node_handle_.advertise<sensor_msgs::PointCloud2>("depth/upright/points", 1); 00131 00132 transform_listener_ = new tf::TransformListener(node_handle_); 00133 00134 // initializations 00135 init(); 00136 00137 std::cout << "CobKinectImageFlipNodelet initilized.\n"; 00138 } 00139 00140 unsigned long init() 00141 { 00142 color_camera_image_sub_.subscribe(*it_, "colorimage", 1); 00143 point_cloud_sub_.subscribe(node_handle_, "pointcloud", 1); 00144 00145 sync_pointcloud_->connectInput(point_cloud_sub_, color_camera_image_sub_); 00146 sync_pointcloud_callback_connection_ = sync_pointcloud_->registerCallback(boost::bind(&CobKinectImageFlipNodelet::inputCallback, this, _1, _2)); 00147 00148 return ipa_Utils::RET_OK; 00149 } 00150 00151 unsigned long convertColorImageMessageToMat(const sensor_msgs::Image::ConstPtr& color_image_msg, cv_bridge::CvImageConstPtr& color_image_ptr, cv::Mat& color_image) 00152 { 00153 try 00154 { 00155 color_image_ptr = cv_bridge::toCvShare(color_image_msg, sensor_msgs::image_encodings::BGR8); 00156 } 00157 catch (cv_bridge::Exception& e) 00158 { 00159 ROS_ERROR("PeopleDetection: cv_bridge exception: %s", e.what()); 00160 return ipa_Utils::RET_FAILED; 00161 } 00162 color_image = color_image_ptr->image; 00163 00164 return ipa_Utils::RET_OK; 00165 } 00166 00167 void inputCallback(const sensor_msgs::PointCloud2::ConstPtr& point_cloud_msg, const sensor_msgs::Image::ConstPtr& color_image_msg) 00168 { 00169 // check camera link orientation and decide whether image must be turned around 00170 00171 bool turnAround = false; 00172 tf::StampedTransform transform; 00173 try 00174 { 00175 transform_listener_->lookupTransform("/base_link", "/head_cam3d_link", ros::Time(0), transform); 00176 btScalar roll, pitch, yaw; 00177 transform.getBasis().getRPY(roll, pitch, yaw, 1); 00178 if (roll > 0.0) turnAround = true; 00179 // std::cout << "xyz: " << transform.getOrigin().getX() << " " << transform.getOrigin().getY() << " " << transform.getOrigin().getZ() << "\n"; 00180 // std::cout << "abcw: " << transform.getRotation().getX() << " " << transform.getRotation().getY() << " " << transform.getRotation().getZ() << " " << transform.getRotation().getW() << "\n"; 00181 // std::cout << "rpy: " << roll << " " << pitch << " " << yaw << "\n"; 00182 } 00183 catch (tf::TransformException ex) 00184 { 00185 ROS_WARN("%s",ex.what()); 00186 } 00187 00188 if (turnAround==false) 00189 { 00190 // image upright, robot is watching backwards 00191 sensor_msgs::Image color_image_turned_msg = *color_image_msg; 00192 color_image_turned_msg.header.stamp = ros::Time::now(); 00193 color_camera_image_pub_.publish(color_image_turned_msg); 00194 sensor_msgs::PointCloud2 point_cloud_turned_msg = *point_cloud_msg; 00195 point_cloud_turned_msg.header.stamp = ros::Time::now(); 00196 point_cloud_pub_.publish(point_cloud_turned_msg); 00197 } 00198 else 00199 { 00200 // image upside down, robot is watching forwards 00201 // read input 00202 // color 00203 cv_bridge::CvImageConstPtr color_image_ptr; 00204 cv::Mat color_image; 00205 convertColorImageMessageToMat(color_image_msg, color_image_ptr, color_image); 00206 00207 // point cloud 00208 pcl::PointCloud<pcl::PointXYZ> point_cloud_src; 00209 pcl::fromROSMsg(*point_cloud_msg, point_cloud_src); 00210 00211 // rotate images by 180 degrees 00212 // color 00213 cv::Mat color_image_turned(color_image.rows, color_image.cols, color_image.type()); 00214 if (color_image.type() != CV_8UC3) 00215 { 00216 std::cout << "CobKinectImageFlipNodelet::inputCallback: Error: The image format of the color image is not CV_8UC3.\n"; 00217 return; 00218 } 00219 for (int v=0; v<color_image.rows; v++) 00220 { 00221 uchar* src = color_image.ptr(v); 00222 uchar* dst = color_image_turned.ptr(color_image.rows-v-1); 00223 dst += 3*(color_image.cols-1); 00224 for (int u=0; u<color_image.cols; u++) 00225 { 00226 for (int k=0; k<3; k++) 00227 { 00228 *dst = *src; 00229 src++; dst++; 00230 } 00231 dst -= 6; 00232 } 00233 } 00234 00235 // point cloud 00236 pcl::PointCloud<pcl::PointXYZ>::Ptr point_cloud_turned(new pcl::PointCloud<pcl::PointXYZ>); 00237 for (int v=(int)point_cloud_src.height-1; v>=0; v--) 00238 { 00239 for (int u=(int)point_cloud_src.width-1; u>=0; u--) 00240 { 00241 point_cloud_turned->push_back(point_cloud_src(u,v)); 00242 } 00243 } 00244 00245 // publish turned data 00246 // color 00247 cv_bridge::CvImage cv_ptr; 00248 cv_ptr.image = color_image_turned; 00249 cv_ptr.encoding = "bgr8"; 00250 sensor_msgs::Image::Ptr color_image_turned_msg = cv_ptr.toImageMsg(); 00251 color_image_turned_msg->header.stamp = ros::Time::now(); //color_image_msg->header.stamp; 00252 color_camera_image_pub_.publish(color_image_turned_msg); 00253 00254 00255 // point cloud 00256 point_cloud_turned->header = point_cloud_msg->header; 00257 point_cloud_turned->height = point_cloud_msg->height; 00258 point_cloud_turned->width = point_cloud_msg->width; 00259 //point_cloud_turned->sensor_orientation_ = point_cloud_msg->sensor_orientation_; 00260 //point_cloud_turned->sensor_origin_ = point_cloud_msg->sensor_origin_; 00261 point_cloud_turned->is_dense = point_cloud_msg->is_dense; 00262 sensor_msgs::PointCloud2::Ptr point_cloud_turned_msg(new sensor_msgs::PointCloud2); 00263 pcl::toROSMsg(*point_cloud_turned, *point_cloud_turned_msg); 00264 point_cloud_turned_msg->header.stamp = ros::Time::now(); 00265 point_cloud_pub_.publish(point_cloud_turned_msg); 00266 00267 // cv::namedWindow("test"); 00268 // cv::imshow("test", color_image_turned); 00269 // cv::waitKey(10); 00270 } 00271 } 00272 }; 00273 00274 } 00275 00276 PLUGINLIB_DECLARE_CLASS(ipa_CameraSensors, CobKinectImageFlipNodelet, ipa_CameraSensors::CobKinectImageFlipNodelet, nodelet::Nodelet)