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 #include "OdometryROS.h"
00029
00030 #include <message_filters/subscriber.h>
00031 #include <message_filters/time_synchronizer.h>
00032 #include <message_filters/sync_policies/approximate_time.h>
00033
00034 #include <image_transport/image_transport.h>
00035 #include <image_transport/subscriber_filter.h>
00036
00037 #include <image_geometry/stereo_camera_model.h>
00038
00039 #include <sensor_msgs/Image.h>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042
00043 #include "rtabmap_ros/MsgConversion.h"
00044
00045 #include <rtabmap/utilite/ULogger.h>
00046
00047 using namespace rtabmap;
00048
00049 class RGBDOdometry : public rtabmap_ros::OdometryROS
00050 {
00051 public:
00052 RGBDOdometry(int argc, char * argv[]) :
00053 rtabmap_ros::OdometryROS(argc, argv),
00054 sync_(0)
00055 {
00056 ros::NodeHandle nh;
00057 ros::NodeHandle pnh("~");
00058
00059 int queueSize = 5;
00060 pnh.param("queue_size", queueSize, queueSize);
00061
00062 ros::NodeHandle rgb_nh(nh, "rgb");
00063 ros::NodeHandle depth_nh(nh, "depth");
00064 ros::NodeHandle rgb_pnh(pnh, "rgb");
00065 ros::NodeHandle depth_pnh(pnh, "depth");
00066 image_transport::ImageTransport rgb_it(rgb_nh);
00067 image_transport::ImageTransport depth_it(depth_nh);
00068 image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
00069 image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
00070
00071 image_mono_sub_.subscribe(rgb_it, rgb_nh.resolveName("image"), 1, hintsRgb);
00072 image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image"), 1, hintsDepth);
00073 info_sub_.subscribe(rgb_nh, "camera_info", 1);
00074
00075 ROS_INFO("\n%s subscribed to:\n %s,\n %s,\n %s",
00076 ros::this_node::getName().c_str(),
00077 image_mono_sub_.getTopic().c_str(),
00078 image_depth_sub_.getTopic().c_str(),
00079 info_sub_.getTopic().c_str());
00080
00081 sync_ = new message_filters::Synchronizer<MySyncPolicy>(MySyncPolicy(queueSize), image_mono_sub_, image_depth_sub_, info_sub_);
00082 sync_->registerCallback(boost::bind(&RGBDOdometry::callback, this, _1, _2, _3));
00083 }
00084
00085 ~RGBDOdometry()
00086 {
00087 delete sync_;
00088 }
00089
00090 void callback(const sensor_msgs::ImageConstPtr& image,
00091 const sensor_msgs::ImageConstPtr& depth,
00092 const sensor_msgs::CameraInfoConstPtr& cameraInfo)
00093 {
00094 if(!this->isPaused())
00095 {
00096 if(!(image->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
00097 image->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
00098 image->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
00099 image->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0) ||
00100 !(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_16UC1)==0 ||
00101 depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0 ||
00102 depth->encoding.compare(sensor_msgs::image_encodings::MONO16)==0))
00103 {
00104 ROS_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 recommended) and image_depth=16UC1,32FC1,mono16");
00105 return;
00106 }
00107 else if(depth->encoding.compare(sensor_msgs::image_encodings::TYPE_32FC1)==0)
00108 {
00109 static bool warned = false;
00110 if(!warned)
00111 {
00112 ROS_WARN("Input depth type is 32FC1, please use type 16UC1 or mono16 for depth. The depth images "
00113 "will be processed anyway but with a conversion. This warning is only be printed once...");
00114 warned = true;
00115 }
00116 }
00117
00118 tf::StampedTransform localTransform;
00119 try
00120 {
00121 if(this->waitForTransform())
00122 {
00123 if(!this->tfListener().waitForTransform(this->frameId(), image->header.frame_id, image->header.stamp, ros::Duration(1)))
00124 {
00125 ROS_WARN("Could not get transform from %s to %s after 1 second!", this->frameId().c_str(), image->header.frame_id.c_str());
00126 return;
00127 }
00128 }
00129 this->tfListener().lookupTransform(this->frameId(), image->header.frame_id, image->header.stamp, localTransform);
00130 }
00131 catch(tf::TransformException & ex)
00132 {
00133 ROS_WARN("%s",ex.what());
00134 return;
00135 }
00136
00137 if(image->data.size() && depth->data.size() && cameraInfo->K[4] != 0)
00138 {
00139 image_geometry::PinholeCameraModel model;
00140 model.fromCameraInfo(*cameraInfo);
00141 float fx = model.fx();
00142 float fy = model.fy();
00143 float cx = model.cx();
00144 float cy = model.cy();
00145 cv_bridge::CvImageConstPtr ptrImage = cv_bridge::toCvShare(image, "mono8");
00146 cv_bridge::CvImageConstPtr ptrDepth = cv_bridge::toCvShare(depth);
00147
00148 rtabmap::SensorData data(
00149 ptrImage->image,
00150 ptrDepth->image,
00151 fx,
00152 fy,
00153 cx,
00154 cy,
00155 rtabmap_ros::transformFromTF(localTransform),
00156 rtabmap::Transform(),
00157 1.0f,
00158 1.0f,
00159 0,
00160 rtabmap_ros::timestampFromROS(image->header.stamp));
00161
00162 this->processData(data, image->header);
00163 }
00164 }
00165 }
00166
00167 private:
00168 image_transport::SubscriberFilter image_mono_sub_;
00169 image_transport::SubscriberFilter image_depth_sub_;
00170 message_filters::Subscriber<sensor_msgs::CameraInfo> info_sub_;
00171 typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo> MySyncPolicy;
00172 message_filters::Synchronizer<MySyncPolicy> * sync_;
00173 };
00174
00175 int main(int argc, char *argv[])
00176 {
00177 ULogger::setType(ULogger::kTypeConsole);
00178 ULogger::setLevel(ULogger::kWarning);
00179 ros::init(argc, argv, "rgbd_odometry");
00180
00181 RGBDOdometry odom(argc, argv);
00182 ros::spin();
00183 return 0;
00184 }