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_sync {
31 
33  const nav_msgs::OdometryConstPtr& odomMsg)
34 {
35  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
36  sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
37  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
38  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
39 }
40 void CommonDataSubscriber::odomInfoCallback(
41  const nav_msgs::OdometryConstPtr& odomMsg,
42  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
43 {
44  rtabmap_msgs::UserDataConstPtr userDataMsg; // Null
45  sensor_msgs::LaserScanConstPtr scan2dMsg; // Null
46  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
47 }
48 #ifdef RTABMAP_SYNC_USER_DATA
49 void CommonDataSubscriber::odomDataCallback(
50  const nav_msgs::OdometryConstPtr& odomMsg,
51  const rtabmap_msgs::UserDataConstPtr & userDataMsg)
52 {
53  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
54  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
55 }
56 void CommonDataSubscriber::odomDataInfoCallback(
57  const nav_msgs::OdometryConstPtr& odomMsg,
58  const rtabmap_msgs::UserDataConstPtr & userDataMsg,
59  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
60 {
61  sensor_msgs::PointCloud2ConstPtr scan3dMsg; // Null
62  commonOdomCallback(odomMsg, userDataMsg, odomInfoMsg);
63 }
64 #endif
65 
67  ros::NodeHandle & nh,
68  ros::NodeHandle & pnh,
69  bool subscribeUserData,
70  bool subscribeOdomInfo)
71 {
72  ROS_INFO("Setup scan callback");
73 
74  if(subscribeUserData || subscribeOdomInfo)
75  {
76  odomSub_.subscribe(nh, "odom", topicQueueSize_);
77 
78 #ifdef RTABMAP_SYNC_USER_DATA
79  if(subscribeUserData)
80  {
81  userDataSub_.subscribe(nh, "user_data", topicQueueSize_);
82  if(subscribeOdomInfo)
83  {
84  subscribedToOdomInfo_ = true;
85  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
87  }
88  else
89  {
91  }
92  }
93  else
94 #endif
95  if(subscribeOdomInfo)
96  {
97  subscribedToOdomInfo_ = true;
98  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
100  }
101  }
102  else
103  {
106  uFormat("\n%s subscribed to:\n %s",
108  odomSubOnly_.getTopic().c_str());
109  }
110 }
111 
112 } /* namespace rtabmap_sync */
rtabmap_sync::CommonDataSubscriber::setupOdomCallbacks
void setupOdomCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeUserData, bool subscribeOdomInfo)
Definition: CommonDataSubscriberOdom.cpp:66
SYNC_DECL2
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
Definition: CommonDataSubscriberDefines.h:108
rtabmap_sync
Definition: CommonDataSubscriber.h:59
uFormat
std::string uFormat(const char *fmt,...)
ros::Subscriber::getTopic
std::string getTopic() const
SYNC_DECL3
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
Definition: CommonDataSubscriberDefines.h:127
rtabmap_sync::CommonDataSubscriber::odomSubOnly_
ros::Subscriber odomSubOnly_
Definition: CommonDataSubscriber.h:293
rtabmap_sync::CommonDataSubscriber::commonOdomCallback
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)=0
rtabmap_sync::CommonDataSubscriber::odomInfoSub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > odomInfoSub_
Definition: CommonDataSubscriber.h:288
rtabmap_sync::CommonDataSubscriber::subscribedTopicsMsg_
std::string subscribedTopicsMsg_
Definition: CommonDataSubscriber.h:244
CommonDataSubscriber.h
rtabmap_sync::CommonDataSubscriber::syncQueueSize_
int syncQueueSize_
Definition: CommonDataSubscriber.h:246
rtabmap_sync::CommonDataSubscriber::topicQueueSize_
int topicQueueSize_
Definition: CommonDataSubscriber.h:245
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
message_filters::Subscriber::subscribe
void subscribe()
rtabmap_sync::CommonDataSubscriber::odomCallback
void odomCallback(const nav_msgs::OdometryConstPtr &)
Definition: CommonDataSubscriberOdom.cpp:32
ros::this_node::getName
const ROSCPP_DECL std::string & getName()
rtabmap_sync::CommonDataSubscriber::approxSync_
bool approxSync_
Definition: CommonDataSubscriber.h:249
rtabmap_sync::CommonDataSubscriber::odomSub_
message_filters::Subscriber< nav_msgs::Odometry > odomSub_
Definition: CommonDataSubscriber.h:283
c_str
const char * c_str(Args &&...args)
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
ROS_INFO
#define ROS_INFO(...)
rtabmap_sync::CommonDataSubscriber::userDataSub_
message_filters::Subscriber< rtabmap_msgs::UserData > userDataSub_
Definition: CommonDataSubscriber.h:284
rtabmap_sync::CommonDataSubscriber
Definition: CommonDataSubscriber.h:61
ros::NodeHandle


rtabmap_sync
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:39:12