data_odom_sync.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 
28 #include "ros/ros.h"
30 #include "nodelet/nodelet.h"
31 
35 
38 
39 #include <sensor_msgs/CameraInfo.h>
40 #include <nav_msgs/Odometry.h>
41 
42 namespace rtabmap_ros
43 {
44 
46 {
47 public:
48  //Constructor
50  sync_(0)
51  {
52  }
53 
55  {
56  delete sync_;
57  }
58 
59 private:
60  virtual void onInit()
61  {
63  ros::NodeHandle& private_nh = getPrivateNodeHandle();
64 
65  ros::NodeHandle rgb_nh(nh, "rgb");
66  ros::NodeHandle depth_nh(nh, "depth");
67  ros::NodeHandle rgb_pnh(private_nh, "rgb");
68  ros::NodeHandle depth_pnh(private_nh, "depth");
69  image_transport::ImageTransport rgb_it(rgb_nh);
70  image_transport::ImageTransport depth_it(depth_nh);
71  image_transport::TransportHints hintsRgb("raw", ros::TransportHints(), rgb_pnh);
72  image_transport::TransportHints hintsDepth("raw", ros::TransportHints(), depth_pnh);
73 
74  int queueSize = 10;
75  private_nh.param("queue_size", queueSize, queueSize);
76 
78  sync_->registerCallback(boost::bind(&DataOdomSyncNodelet::callback, this, _1, _2, _3, _4));
79 
80  image_sub_.subscribe(rgb_it, rgb_nh.resolveName("image_in"), 1, hintsRgb);
81  image_depth_sub_.subscribe(depth_it, depth_nh.resolveName("image_in"), 1, hintsDepth);
82  info_sub_.subscribe(rgb_nh, "camera_info_in", 1);
83  odom_sub_.subscribe(nh, "odom_in", 1);
84 
85  imagePub_ = rgb_it.advertise("image_out", 1);
86  imageDepthPub_ = depth_it.advertise("image_out", 1);
87  infoPub_ = rgb_nh.advertise<sensor_msgs::CameraInfo>("camera_info_out", 1);
88  odomPub_ = nh.advertise<nav_msgs::Odometry>("odom_out", 1);
89  };
90 
91  void callback(const sensor_msgs::ImageConstPtr& image,
92  const sensor_msgs::ImageConstPtr& imageDepth,
93  const sensor_msgs::CameraInfoConstPtr& camInfo,
94  const nav_msgs::OdometryConstPtr & odom)
95  {
97  {
98  imagePub_.publish(image);
99  }
101  {
102  imageDepthPub_.publish(imageDepth);
103  }
105  {
106  infoPub_.publish(camInfo);
107  }
109  {
110  odomPub_.publish(odom);
111  }
112  }
113 
118 
125 
126 };
127 
128 
130 }
message_filters::Subscriber< nav_msgs::Odometry > odom_sub_
message_filters::Subscriber< sensor_msgs::CameraInfo > info_sub_
void publish(const boost::shared_ptr< M > &message) const
image_transport::SubscriberFilter image_depth_sub_
std::string resolveName(const std::string &name, bool remap=true) const
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
image_transport::Publisher imageDepthPub_
image_transport::Publisher imagePub_
uint32_t getNumSubscribers() const
ros::NodeHandle & getPrivateNodeHandle() const
void callback(const sensor_msgs::ImageConstPtr &image, const sensor_msgs::ImageConstPtr &imageDepth, const sensor_msgs::CameraInfoConstPtr &camInfo, const nav_msgs::OdometryConstPtr &odom)
void publish(const sensor_msgs::Image &message) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, nav_msgs::Odometry > MySyncPolicy
message_filters::Synchronizer< MySyncPolicy > * sync_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::NodeHandle & getNodeHandle() const
uint32_t getNumSubscribers() const
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
image_transport::SubscriberFilter image_sub_
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19