CommonDataSubscriberSensorData.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 
32 #include <cv_bridge/cv_bridge.h>
33 
34 namespace rtabmap_sync {
35 
36 // SensorData
38  const rtabmap_msgs::SensorDataConstPtr& imagesMsg)
39 {
40  nav_msgs::OdometryConstPtr odomMsg; // Null
41  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
42  commonSensorDataCallback(imagesMsg, odomMsg, odomInfoMsg);
43 }
44 void CommonDataSubscriber::sensorDataInfoCallback(
45  const rtabmap_msgs::SensorDataConstPtr& imagesMsg,
46  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
47 {
48  nav_msgs::OdometryConstPtr odomMsg; // Null
49  commonSensorDataCallback(imagesMsg, odomMsg, odomInfoMsg);
50 }
51 // SensorData + Odom
52 void CommonDataSubscriber::sensorDataOdomCallback(
53  const nav_msgs::OdometryConstPtr & odomMsg,
54  const rtabmap_msgs::SensorDataConstPtr& imagesMsg)
55 {
56  rtabmap_msgs::OdomInfoConstPtr odomInfoMsg; // null
57  commonSensorDataCallback(imagesMsg, odomMsg, odomInfoMsg);
58 }
59 void CommonDataSubscriber::sensorDataOdomInfoCallback(
60  const nav_msgs::OdometryConstPtr & odomMsg,
61  const rtabmap_msgs::SensorDataConstPtr& imagesMsg,
62  const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg)
63 {
64  commonSensorDataCallback(imagesMsg, odomMsg, odomInfoMsg);
65 }
66 
68  ros::NodeHandle & nh,
69  ros::NodeHandle & pnh,
70  bool subscribeOdom,
71  bool subscribeOdomInfo)
72 {
73  ROS_INFO("Setup SensorData callback");
74 
75  sensorDataSub_.subscribe(nh, "sensor_data", topicQueueSize_);
76  if(subscribeOdom)
77  {
78  odomSub_.subscribe(nh, "odom", topicQueueSize_);
79  if(subscribeOdomInfo)
80  {
81  subscribedToOdomInfo_ = true;
82  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
84  }
85  else
86  {
88  }
89  }
90  else
91  {
92  if(subscribeOdomInfo)
93  {
94  subscribedToOdomInfo_ = true;
95  odomInfoSub_.subscribe(nh, "odom_info", topicQueueSize_);
97  }
98  else
99  {
102 
104  uFormat("\n%s subscribed to:\n %s",
106  sensorDataSubOnly_.getTopic().c_str());
107  }
108  }
109 }
110 
111 } /* namespace rtabmap_sync */
rtabmap_sync::CommonDataSubscriber::setupSensorDataCallbacks
void setupSensorDataCallbacks(ros::NodeHandle &nh, ros::NodeHandle &pnh, bool subscribeOdom, bool subscribeOdomInfo)
Definition: CommonDataSubscriberSensorData.cpp:67
SYNC_DECL2
#define SYNC_DECL2(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1)
Definition: CommonDataSubscriberDefines.h:108
rtabmap_sync::CommonDataSubscriber::sensorDataSubOnly_
ros::Subscriber sensorDataSubOnly_
Definition: CommonDataSubscriber.h:274
rtabmap_sync
Definition: CommonDataSubscriber.h:59
uFormat
std::string uFormat(const char *fmt,...)
Compression.h
ros::Subscriber::getTopic
std::string getTopic() const
SYNC_DECL3
#define SYNC_DECL3(CLASS, PREFIX, APPROX, QUEUE_SIZE, SUB0, SUB1, SUB2)
Definition: CommonDataSubscriberDefines.h:127
message_filters::Subscriber::unsubscribe
void unsubscribe()
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::commonSensorDataCallback
virtual void commonSensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &sensorDataMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)=0
rtabmap_sync::CommonDataSubscriber::topicQueueSize_
int topicQueueSize_
Definition: CommonDataSubscriber.h:245
rtabmap_sync::CommonDataSubscriber::sensorDataCallback
void sensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &)
Definition: CommonDataSubscriberSensorData.cpp:37
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()
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)
cv_bridge.h
rtabmap_sync::CommonDataSubscriber::subscribedToOdomInfo_
bool subscribedToOdomInfo_
Definition: CommonDataSubscriber.h:259
ROS_INFO
#define ROS_INFO(...)
UConversion.h
MsgConversion.h
rtabmap_sync::CommonDataSubscriber::sensorDataSub_
message_filters::Subscriber< rtabmap_msgs::SensorData > sensorDataSub_
Definition: CommonDataSubscriber.h:275
rtabmap_sync::CommonDataSubscriber
Definition: CommonDataSubscriber.h:61
ros::NodeHandle


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