#include <ros/ros.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/PoseStamped.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <geometry_msgs/TransformStamped.h>
#include <sensor_msgs/Imu.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <tf/transform_datatypes.h>
#include <topic_tools/shape_shifter.h>
Go to the source code of this file.
Namespaces | |
tf | |
Typedefs | |
typedef btMatrix3x3 | tf::Matrix3x3 |
typedef btScalar | tfScalar |
Functions | |
void | addTransform (std::vector< geometry_msgs::TransformStamped > &transforms, const tf::StampedTransform &tf) |
void | imuCallback (sensor_msgs::Imu const &imu) |
int | main (int argc, char **argv) |
void | multiCallback (topic_tools::ShapeShifter const &input) |
void | odomCallback (nav_msgs::Odometry const &odometry) |
void | poseCallback (geometry_msgs::PoseStamped const &pose) |
void | sendTransform (geometry_msgs::Pose const &pose, const std_msgs::Header &header, std::string child_frame_id="") |
void | tfCallback (geometry_msgs::TransformStamped const &tf) |
Variables | |
std::string | g_child_frame_id |
ros::Publisher | g_euler_publisher |
std::string | g_footprint_frame_id |
std::string | g_frame_id |
std::string | g_imu_topic |
std::string | g_odometry_topic |
ros::Publisher | g_pose_publisher |
std::string | g_pose_topic |
std::string | g_position_frame_id |
bool | g_publish_roll_pitch |
std::string | g_stabilized_frame_id |
std::string | g_tf_prefix |
std::string | g_topic |
tf::TransformBroadcaster * | g_transform_broadcaster |
typedef btScalar tfScalar |
Definition at line 57 of file message_to_tf.cc.
void addTransform | ( | std::vector< geometry_msgs::TransformStamped > & | transforms, |
const tf::StampedTransform & | tf | ||
) |
Definition at line 61 of file message_to_tf.cc.
void imuCallback | ( | sensor_msgs::Imu const & | imu | ) |
Definition at line 167 of file message_to_tf.cc.
int main | ( | int | argc, |
char ** | argv | ||
) |
Definition at line 232 of file message_to_tf.cc.
void multiCallback | ( | topic_tools::ShapeShifter const & | input | ) |
Definition at line 204 of file message_to_tf.cc.
void odomCallback | ( | nav_msgs::Odometry const & | odometry | ) |
Definition at line 149 of file message_to_tf.cc.
void poseCallback | ( | geometry_msgs::PoseStamped const & | pose | ) |
Definition at line 153 of file message_to_tf.cc.
void sendTransform | ( | geometry_msgs::Pose const & | pose, |
const std_msgs::Header & | header, | ||
std::string | child_frame_id = "" |
||
) |
Definition at line 67 of file message_to_tf.cc.
void tfCallback | ( | geometry_msgs::TransformStamped const & | tf | ) |
Definition at line 157 of file message_to_tf.cc.
std::string g_child_frame_id |
Definition at line 46 of file message_to_tf.cc.
ros::Publisher g_euler_publisher |
Definition at line 54 of file message_to_tf.cc.
std::string g_footprint_frame_id |
Definition at line 43 of file message_to_tf.cc.
std::string g_frame_id |
Definition at line 42 of file message_to_tf.cc.
std::string g_imu_topic |
Definition at line 40 of file message_to_tf.cc.
std::string g_odometry_topic |
Definition at line 38 of file message_to_tf.cc.
ros::Publisher g_pose_publisher |
Definition at line 53 of file message_to_tf.cc.
std::string g_pose_topic |
Definition at line 39 of file message_to_tf.cc.
std::string g_position_frame_id |
Definition at line 44 of file message_to_tf.cc.
bool g_publish_roll_pitch |
Definition at line 48 of file message_to_tf.cc.
std::string g_stabilized_frame_id |
Definition at line 45 of file message_to_tf.cc.
std::string g_tf_prefix |
Definition at line 50 of file message_to_tf.cc.
std::string g_topic |
Definition at line 41 of file message_to_tf.cc.
tf::TransformBroadcaster* g_transform_broadcaster |
Definition at line 52 of file message_to_tf.cc.