include
rsm_additions
GazeboToTf.h
Go to the documentation of this file.
1
/*
2
* GazeboToTf.h
3
*
4
* Created on: Oct 25, 2020
5
* Author: marco
6
*/
7
8
#ifndef GAZEBOTOTF_H_
9
#define GAZEBOTOTF_H_
10
11
#include "
ros/ros.h
"
12
#include "nav_msgs/Odometry.h"
13
#include <
tf2/LinearMath/Quaternion.h
>
14
#include <
tf2_ros/transform_broadcaster.h
>
15
#include <geometry_msgs/TransformStamped.h>
16
17
namespace
rsm
{
18
19
class
GazeboToTf
{
20
public
:
21
GazeboToTf
();
22
virtual
~GazeboToTf
();
23
private
:
24
std::string
_odom_topic
,
_map_frame
,
_robot_frame
;
25
ros::NodeHandle
_nh
;
26
ros::Subscriber
_odom_subscriber
;
27
tf2_ros::TransformBroadcaster
_tf_broadcaster
;
28
29
void
odomCallback
(
const
nav_msgs::Odometry::ConstPtr &msg);
30
};
31
32
}
33
34
#endif
/* GAZEBOTOTF_H_ */
Quaternion.h
rsm::GazeboToTf::odomCallback
void odomCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition:
GazeboToTf.cpp:28
rsm::GazeboToTf::_odom_topic
std::string _odom_topic
Definition:
GazeboToTf.h:24
ros::NodeHandle
rsm::GazeboToTf::_odom_subscriber
ros::Subscriber _odom_subscriber
Definition:
GazeboToTf.h:26
rsm::GazeboToTf::_tf_broadcaster
tf2_ros::TransformBroadcaster _tf_broadcaster
Definition:
GazeboToTf.h:27
rsm::GazeboToTf::GazeboToTf
GazeboToTf()
Definition:
GazeboToTf.cpp:12
rsm::GazeboToTf::~GazeboToTf
virtual ~GazeboToTf()
Definition:
GazeboToTf.cpp:24
transform_broadcaster.h
rsm::GazeboToTf::_nh
ros::NodeHandle _nh
Definition:
GazeboToTf.h:25
ros::Subscriber
rsm
rsm::GazeboToTf::_map_frame
std::string _map_frame
Definition:
GazeboToTf.h:24
ros.h
tf2_ros::TransformBroadcaster
rsm::GazeboToTf::_robot_frame
std::string _robot_frame
Definition:
GazeboToTf.h:24
rsm::GazeboToTf
Definition:
GazeboToTf.h:19
rsm_additions
Author(s): Marco Steinbrink
autogenerated on Mon Feb 28 2022 23:28:21