stereo_odometry.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
30 #include "nodelet/nodelet.h"
31 
35 
38 
39 #include <sensor_msgs/Image.h>
41 #include <sensor_msgs/Imu.h>
42 
44 
45 #include <cv_bridge/cv_bridge.h>
46 
48 
50 #include <rtabmap/utilite/UTimer.h>
51 #include <rtabmap/utilite/UStl.h>
53 #include <rtabmap/core/Odometry.h>
54 
55 using namespace rtabmap;
56 
57 namespace rtabmap_ros
58 {
59 
61 {
62 public:
65  approxSync_(0),
66  exactSync_(0),
67  queueSize_(5)
68  {
69  }
70 
71  virtual ~StereoOdometry()
72  {
73  if(approxSync_)
74  {
75  delete approxSync_;
76  }
77  if(exactSync_)
78  {
79  delete exactSync_;
80  }
81  }
82 
83 private:
84  virtual void onOdomInit()
85  {
86  ros::NodeHandle & nh = getNodeHandle();
87  ros::NodeHandle & pnh = getPrivateNodeHandle();
88 
89  bool approxSync = false;
90  bool subscribeRGBD = false;
91  pnh.param("approx_sync", approxSync, approxSync);
92  pnh.param("queue_size", queueSize_, queueSize_);
93  pnh.param("subscribe_rgbd", subscribeRGBD, subscribeRGBD);
94 
95  NODELET_INFO("StereoOdometry: approx_sync = %s", approxSync?"true":"false");
96  NODELET_INFO("StereoOdometry: queue_size = %d", queueSize_);
97  NODELET_INFO("StereoOdometry: subscribe_rgbd = %s", subscribeRGBD?"true":"false");
98 
99  std::string subscribedTopicsMsg;
100  if(subscribeRGBD)
101  {
102  rgbdSub_ = nh.subscribe("rgbd_image", 1, &StereoOdometry::callbackRGBD, this);
103 
104  subscribedTopicsMsg =
105  uFormat("\n%s subscribed to:\n %s",
106  getName().c_str(),
107  rgbdSub_.getTopic().c_str());
108  }
109  else
110  {
111  ros::NodeHandle left_nh(nh, "left");
112  ros::NodeHandle right_nh(nh, "right");
113  ros::NodeHandle left_pnh(pnh, "left");
114  ros::NodeHandle right_pnh(pnh, "right");
115  image_transport::ImageTransport left_it(left_nh);
116  image_transport::ImageTransport right_it(right_nh);
117  image_transport::TransportHints hintsLeft("raw", ros::TransportHints(), left_pnh);
118  image_transport::TransportHints hintsRight("raw", ros::TransportHints(), right_pnh);
119 
120  imageRectLeft_.subscribe(left_it, left_nh.resolveName("image_rect"), 1, hintsLeft);
121  imageRectRight_.subscribe(right_it, right_nh.resolveName("image_rect"), 1, hintsRight);
122  cameraInfoLeft_.subscribe(left_nh, "camera_info", 1);
123  cameraInfoRight_.subscribe(right_nh, "camera_info", 1);
124 
125  if(approxSync)
126  {
127  approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
128  approxSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
129  }
130  else
131  {
132  exactSync_ = new message_filters::Synchronizer<MyExactSyncPolicy>(MyExactSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
133  exactSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
134  }
135 
136 
137  subscribedTopicsMsg = uFormat("\n%s subscribed to (%s sync):\n %s,\n %s,\n %s,\n %s",
138  getName().c_str(),
139  approxSync?"approx":"exact",
140  imageRectLeft_.getTopic().c_str(),
141  imageRectRight_.getTopic().c_str(),
142  cameraInfoLeft_.getTopic().c_str(),
143  cameraInfoRight_.getTopic().c_str());
144  }
145 
146  int odomStrategy = 0;
147  Parameters::parse(this->parameters(), Parameters::kOdomStrategy(), odomStrategy);
148  if(odomStrategy == Odometry::kTypeOkvis || odomStrategy == Odometry::kTypeMSCKF)
149  {
150  imuSub_ = nh.subscribe("imu", queueSize_*5, &StereoOdometry::callbackIMU, this);
151  NODELET_INFO("VIO approach selected, subscribing to IMU topic %s", imuSub_.getTopic().c_str());
152  }
153 
154  this->startWarningThread(subscribedTopicsMsg, approxSync);
155  }
156 
157  virtual void updateParameters(ParametersMap & parameters)
158  {
159  //make sure we are using Reg/Strategy=0
160  ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
161  if(iter != parameters.end() && iter->second.compare("0") != 0)
162  {
163  ROS_WARN("Stereo odometry works only with \"Reg/Strategy\"=0. Ignoring value %s.", iter->second.c_str());
164  }
165  uInsert(parameters, ParametersPair(Parameters::kRegStrategy(), "0"));
166  }
167 
168  void callback(
169  const sensor_msgs::ImageConstPtr& imageRectLeft,
170  const sensor_msgs::ImageConstPtr& imageRectRight,
171  const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
172  const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
173  {
174  callbackCalled();
175  if(!this->isPaused())
176  {
177  if(!(imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
178  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
179  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
180  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0) ||
181  !(imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
182  imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
183  imageRectRight->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
184  imageRectRight->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0))
185  {
186  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 recommended), received types are %s (left) and %s (right)",
187  imageRectLeft->encoding.c_str(), imageRectRight->encoding.c_str());
188  return;
189  }
190 
191  ros::Time stamp = imageRectLeft->header.stamp>imageRectRight->header.stamp?imageRectLeft->header.stamp:imageRectRight->header.stamp;
192 
193  Transform localTransform = getTransform(this->frameId(), imageRectLeft->header.frame_id, stamp);
194  if(localTransform.isNull())
195  {
196  return;
197  }
198 
199  int quality = -1;
200  if(imageRectLeft->data.size() && imageRectRight->data.size())
201  {
202  rtabmap::StereoCameraModel stereoModel = rtabmap_ros::stereoCameraModelFromROS(*cameraInfoLeft, *cameraInfoRight, localTransform);
203  if(stereoModel.baseline() <= 0)
204  {
205  NODELET_FATAL("The stereo baseline (%f) should be positive (baseline=-Tx/fx). We assume a horizontal left/right stereo "
206  "setup where the Tx (or P(0,3)) is negative in the right camera info msg.", stereoModel.baseline());
207  return;
208  }
209 
210  if(stereoModel.baseline() > 10.0)
211  {
212  static bool shown = false;
213  if(!shown)
214  {
215  NODELET_WARN("Detected baseline (%f m) is quite large! Is your "
216  "right camera_info P(0,3) correctly set? Note that "
217  "baseline=-P(0,3)/P(0,0). This warning is printed only once.",
218  stereoModel.baseline());
219  shown = true;
220  }
221  }
222 
223  cv_bridge::CvImagePtr ptrImageLeft = cv_bridge::toCvCopy(imageRectLeft, "mono8");
224  cv_bridge::CvImagePtr ptrImageRight = cv_bridge::toCvCopy(imageRectRight, "mono8");
225 
226  UTimer stepTimer;
227  //
228  UDEBUG("localTransform = %s", localTransform.prettyPrint().c_str());
229  rtabmap::SensorData data(
230  ptrImageLeft->image,
231  ptrImageRight->image,
232  stereoModel,
233  0,
235 
236  this->processData(data, stamp);
237  }
238  else
239  {
240  NODELET_WARN("Odom: input images empty?!?");
241  }
242  }
243  }
244 
246  const rtabmap_ros::RGBDImageConstPtr& image)
247  {
248  callbackCalled();
249  if(!this->isPaused())
250  {
251  cv_bridge::CvImageConstPtr imageRectLeft, imageRectRight;
252  rtabmap_ros::toCvShare(image, imageRectLeft, imageRectRight);
253 
254  if(!(imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
255  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
256  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
257  imageRectLeft->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0) ||
258  !(imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO8) ==0 ||
259  imageRectRight->encoding.compare(sensor_msgs::image_encodings::MONO16) ==0 ||
260  imageRectRight->encoding.compare(sensor_msgs::image_encodings::BGR8) == 0 ||
261  imageRectRight->encoding.compare(sensor_msgs::image_encodings::RGB8) == 0))
262  {
263  NODELET_ERROR("Input type must be image=mono8,mono16,rgb8,bgr8 (mono8 recommended), received types are %s (left) and %s (right)",
264  imageRectLeft->encoding.c_str(), imageRectRight->encoding.c_str());
265  return;
266  }
267 
268  ros::Time stamp = imageRectLeft->header.stamp>imageRectRight->header.stamp?imageRectLeft->header.stamp:imageRectRight->header.stamp;
269 
270  Transform localTransform = getTransform(this->frameId(), imageRectLeft->header.frame_id, stamp);
271  if(localTransform.isNull())
272  {
273  return;
274  }
275 
277 
278  int quality = -1;
279  if(!imageRectLeft->image.empty() && !imageRectRight->image.empty())
280  {
281  rtabmap::StereoCameraModel stereoModel = rtabmap_ros::stereoCameraModelFromROS(image->rgbCameraInfo, image->depthCameraInfo, localTransform);
282  if(stereoModel.baseline() <= 0)
283  {
284  NODELET_FATAL("The stereo baseline (%f) should be positive (baseline=-Tx/fx). We assume a horizontal left/right stereo "
285  "setup where the Tx (or P(0,3)) is negative in the right camera info msg.", stereoModel.baseline());
286  return;
287  }
288 
289  if(stereoModel.baseline() > 10.0)
290  {
291  static bool shown = false;
292  if(!shown)
293  {
294  NODELET_WARN("Detected baseline (%f m) is quite large! Is your "
295  "right camera_info P(0,3) correctly set? Note that "
296  "baseline=-P(0,3)/P(0,0). This warning is printed only once.",
297  stereoModel.baseline());
298  shown = true;
299  }
300  }
301 
302  cv_bridge::CvImagePtr ptrImageLeft = cv_bridge::cvtColor(imageRectLeft, "mono8");
303  cv_bridge::CvImagePtr ptrImageRight = cv_bridge::cvtColor(imageRectRight, "mono8");
304 
305  UTimer stepTimer;
306  //
307  UDEBUG("localTransform = %s", localTransform.prettyPrint().c_str());
308  rtabmap::SensorData data(
309  ptrImageLeft->image,
310  ptrImageRight->image,
311  stereoModel,
312  0,
314 
315  this->processData(data, stamp);
316  }
317  else
318  {
319  NODELET_WARN("Odom: input images empty?!?");
320  }
321  }
322  }
323 
325  const sensor_msgs::ImuConstPtr& msg)
326  {
327  if(!this->isPaused())
328  {
329  double stamp = msg->header.stamp.toSec();
331  if(this->frameId().compare(msg->header.frame_id) != 0)
332  {
333  localTransform = getTransform(this->frameId(), msg->header.frame_id, msg->header.stamp);
334  }
335  if(localTransform.isNull())
336  {
337  ROS_ERROR("Could not transform IMU msg from frame \"%s\" to frame \"%s\", TF not available at time %f",
338  msg->header.frame_id.c_str(), this->frameId().c_str(), stamp);
339  return;
340  }
341 
342  IMU imu(
343  cv::Vec3d(msg->angular_velocity.x, msg->angular_velocity.y, msg->angular_velocity.z),
344  cv::Mat(3,3,CV_64FC1,(void*)msg->angular_velocity_covariance.data()).clone(),
345  cv::Vec3d(msg->linear_acceleration.x, msg->linear_acceleration.y, msg->linear_acceleration.z),
346  cv::Mat(3,3,CV_64FC1,(void*)msg->linear_acceleration_covariance.data()).clone(),
347  localTransform);
348 
349  SensorData data(imu, 0, stamp);
350  this->processData(data, msg->header.stamp);
351  }
352  }
353 
354 protected:
355  virtual void flushCallbacks()
356  {
357  //flush callbacks
358  if(approxSync_)
359  {
360  delete approxSync_;
361  approxSync_ = new message_filters::Synchronizer<MyApproxSyncPolicy>(MyApproxSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
362  approxSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
363  }
364  if(exactSync_)
365  {
366  delete exactSync_;
367  exactSync_ = new message_filters::Synchronizer<MyExactSyncPolicy>(MyExactSyncPolicy(queueSize_), imageRectLeft_, imageRectRight_, cameraInfoLeft_, cameraInfoRight_);
368  exactSync_->registerCallback(boost::bind(&StereoOdometry::callback, this, _1, _2, _3, _4));
369  }
370  }
371 
372 private:
384 };
385 
387 
388 }
389 
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
double baseline() const
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
std::string prettyPrint() const
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
#define NODELET_WARN(...)
image_transport::SubscriberFilter imageRectLeft_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::pair< std::string, std::string > ParametersPair
std::string resolveName(const std::string &name, bool remap=true) const
static Transform getIdentity()
void callback(const sensor_msgs::ImageConstPtr &imageRectLeft, const sensor_msgs::ImageConstPtr &imageRectRight, const sensor_msgs::CameraInfoConstPtr &cameraInfoLeft, const sensor_msgs::CameraInfoConstPtr &cameraInfoRight)
void callbackIMU(const sensor_msgs::ImuConstPtr &msg)
std::string getName(void *handle)
#define ROS_WARN(...)
rtabmap::Transform getTransform(const std::string &fromFrameId, const std::string &toFrameId, const ros::Time &stamp, tf::TransformListener &listener, double waitForTransform)
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoLeft_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::StereoOdometry, nodelet::Nodelet)
image_transport::SubscriberFilter imageRectRight_
#define true
bool isNull() const
Connection registerCallback(C &callback)
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyExactSyncPolicy
CvImagePtr cvtColor(const CvImageConstPtr &source, const std::string &encoding)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
QMap< QString, QVariant > ParametersMap
message_filters::Synchronizer< MyExactSyncPolicy > * exactSync_
message_filters::Subscriber< sensor_msgs::CameraInfo > cameraInfoRight_
const std::string MONO16
virtual void updateParameters(ParametersMap &parameters)
#define false
void callback(rtabmap_ros::CameraConfig &config, uint32_t level)
Definition: CameraNode.cpp:259
#define NODELET_INFO(...)
#define UDEBUG(...)
static WallTime now()
void toCvShare(const rtabmap_ros::RGBDImageConstPtr &image, cv_bridge::CvImageConstPtr &rgb, cv_bridge::CvImageConstPtr &depth)
double timestampFromROS(const ros::Time &stamp)
void callbackRGBD(const rtabmap_ros::RGBDImageConstPtr &image)
#define NODELET_FATAL(...)
#define ROS_ERROR(...)
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > MyApproxSyncPolicy
message_filters::Synchronizer< MyApproxSyncPolicy > * approxSync_
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Fri Jun 7 2019 21:55:04