29 #include <nav_msgs/Odometry.h> 65 ROS_WARN(
"Odometry received is null! Cannot send tf...");
71 t.header.stamp = msg->header.stamp;
86 int main(
int argc,
char** argv)
ros::Subscriber odomTopic_
void odomReceivedCallback(const nav_msgs::OdometryConstPtr &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
int main(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
tf2_ros::TransformBroadcaster tfBroadcaster_