39 #include <sensor_msgs/Image.h> 41 #include <sensor_msgs/Imu.h> 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);
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");
99 std::string subscribedTopicsMsg;
102 rgbdSub_ = nh.
subscribe(
"rgbd_image", 1, &StereoOdometry::callbackRGBD,
this);
104 subscribedTopicsMsg =
105 uFormat(
"\n%s subscribed to:\n %s",
107 rgbdSub_.getTopic().c_str());
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);
137 subscribedTopicsMsg =
uFormat(
"\n%s subscribed to (%s sync):\n %s,\n %s,\n %s,\n %s",
139 approxSync?
"approx":
"exact",
140 imageRectLeft_.getTopic().c_str(),
141 imageRectRight_.getTopic().c_str(),
142 cameraInfoLeft_.getTopic().c_str(),
143 cameraInfoRight_.getTopic().c_str());
146 int odomStrategy = 0;
147 Parameters::parse(this->parameters(), Parameters::kOdomStrategy(), odomStrategy);
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());
154 this->startWarningThread(subscribedTopicsMsg, approxSync);
160 ParametersMap::iterator iter = parameters.find(Parameters::kRegStrategy());
161 if(iter != parameters.end() && iter->second.compare(
"0") != 0)
163 ROS_WARN(
"Stereo odometry works only with \"Reg/Strategy\"=0. Ignoring value %s.", iter->second.c_str());
169 const sensor_msgs::ImageConstPtr& imageRectLeft,
170 const sensor_msgs::ImageConstPtr& imageRectRight,
171 const sensor_msgs::CameraInfoConstPtr& cameraInfoLeft,
172 const sensor_msgs::CameraInfoConstPtr& cameraInfoRight)
175 if(!this->isPaused())
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());
191 ros::Time stamp = imageRectLeft->header.stamp>imageRectRight->header.stamp?imageRectLeft->header.stamp:imageRectRight->header.stamp;
194 if(localTransform.
isNull())
200 if(imageRectLeft->data.size() && imageRectRight->data.size())
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());
212 static bool shown =
false;
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.",
231 ptrImageRight->image,
236 this->processData(data, stamp);
246 const rtabmap_ros::RGBDImageConstPtr& image)
249 if(!this->isPaused())
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());
268 ros::Time stamp = imageRectLeft->header.stamp>imageRectRight->header.stamp?imageRectLeft->header.stamp:imageRectRight->header.stamp;
271 if(localTransform.
isNull())
279 if(!imageRectLeft->image.empty() && !imageRectRight->image.empty())
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());
291 static bool shown =
false;
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.",
310 ptrImageRight->image,
315 this->processData(data, stamp);
325 const sensor_msgs::ImuConstPtr& msg)
327 if(!this->isPaused())
329 double stamp = msg->header.stamp.toSec();
331 if(this->frameId().compare(msg->header.frame_id) != 0)
333 localTransform =
getTransform(this->frameId(), msg->header.frame_id, msg->header.stamp);
335 if(localTransform.
isNull())
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);
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(),
350 this->processData(data, msg->header.stamp);
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
std::string uFormat(const char *fmt,...)
#define NODELET_ERROR(...)
rtabmap::StereoCameraModel stereoCameraModelFromROS(const sensor_msgs::CameraInfo &leftCamInfo, const sensor_msgs::CameraInfo &rightCamInfo, const rtabmap::Transform &localTransform=rtabmap::Transform::getIdentity())
#define NODELET_WARN(...)
virtual void flushCallbacks()
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
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)
virtual ~StereoOdometry()
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_
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 ¶m_name, T ¶m_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_
virtual void updateParameters(ParametersMap ¶meters)
void callback(rtabmap_ros::CameraConfig &config, uint32_t level)
#define NODELET_INFO(...)
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(...)
virtual void onOdomInit()
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)