CommonDataSubscriberOdom.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 
29 
30 namespace rtabmap_ros {
31 
33  const nav_msgs::OdometryConstPtr& odomMsg)
34 {
36  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
37  sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
38  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
39  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
40 }
41 void CommonDataSubscriber::odomInfoCallback(
42  const nav_msgs::OdometryConstPtr& odomMsg,
43  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
44 {
46  rtabmap_ros::UserDataConstPtr userDataMsg; // Null
47  sensor_msgs::LaserScanConstPtr scan2dMsg; // Null
48  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
49 }
50 #ifdef RTABMAP_SYNC_USER_DATA
51 void CommonDataSubscriber::odomDataCallback(
52  const nav_msgs::OdometryConstPtr& odomMsg,
53  const rtabmap_ros::UserDataConstPtr & userDataMsg)
54 {
56  rtabmap_ros::OdomInfoConstPtr odomInfoMsg; // null
57  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
58 }
59 void CommonDataSubscriber::odomDataInfoCallback(
60  const nav_msgs::OdometryConstPtr& odomMsg,
61  const rtabmap_ros::UserDataConstPtr & userDataMsg,
62  const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg)
63 {
65  sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
66  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
67 }
68 #endif
69 
71  ros::NodeHandle & nh,
72  ros::NodeHandle & pnh,
73  bool subscribeUserData,
74  bool subscribeOdomInfo,
75  int queueSize,
76  bool approxSync)
77 {
78  ROS_INFO("Setup scan callback");
79 
80  if(subscribeUserData || subscribeOdomInfo)
81  {
82  odomSub_.subscribe(nh, "odom", queueSize);
83 
84 #ifdef RTABMAP_SYNC_USER_DATA
85  if(subscribeUserData)
86  {
87  userDataSub_.subscribe(nh, "user_data", queueSize);
88  if(subscribeOdomInfo)
89  {
90  subscribedToOdomInfo_ = true;
91  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
92  SYNC_DECL3(odomDataInfo, approxSync, queueSize, odomSub_, userDataSub_, odomInfoSub_);
93  }
94  else
95  {
96  SYNC_DECL2(odomData, approxSync, queueSize, odomSub_, userDataSub_);
97  }
98  }
99  else
100 #endif
101  if(subscribeOdomInfo)
102  {
103  subscribedToOdomInfo_ = true;
104  odomInfoSub_.subscribe(nh, "odom_info", queueSize);
105  SYNC_DECL2(odomInfo, approxSync, queueSize, odomSub_, odomInfoSub_);
106  }
107  }
108  else
109  {
110  odomSubOnly_ = nh.subscribe("odom", queueSize, &CommonDataSubscriber::odomCallback, this);
112  uFormat("\n%s subscribed to:\n %s",
113  ros::this_node::getName().c_str(),
114  odomSubOnly_.getTopic().c_str());
115  }
116 }
117 
118 } /* namespace rtabmap_ros */
std::string uFormat(const char *fmt,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL const std::string & getName()
#define SYNC_DECL3(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
message_filters::Subscriber< rtabmap_ros::UserData > userDataSub_
message_filters::Subscriber< rtabmap_ros::OdomInfo > odomInfoSub_
void setupOdomCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeUserData, bool subscribeOdomInfo, int queueSize, bool approxSync)
#define ROS_INFO(...)
std::string getTopic() const
#define SYNC_DECL2(PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::UserDataConstPtr &userDataMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg)=0
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)
void odomCallback(const nav_msgs::OdometryConstPtr &)


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