Go to the documentation of this file.
4 #include "geometry_msgs/Twist.h"
6 #include "geometry_msgs/PoseWithCovarianceStamped.h"
7 #include "nav_msgs/Odometry.h"
14 #ifndef MOBILE_ROBOT_SIMULATOR
15 #define MOBILE_ROBOT_SIMULATOR
48 void vel_callback(
const geometry_msgs::Twist::ConstPtr& msg);
51 void init_pose_callback(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& msg);
tf::StampedTransform map_trans
tf::TransformBroadcaster tf_broadcaster
void get_tf_from_odom(nav_msgs::Odometry odom)
std::string base_link_frame
void vel_callback(const geometry_msgs::Twist::ConstPtr &msg)
bool publish_map_transform
void update_loop(const ros::TimerEvent &event)
void init_pose_callback(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
std::string velocity_topic
ros::Subscriber init_pose_sub
void update_odom_from_vel(geometry_msgs::Twist vel, ros::Duration time_diff)
MobileRobotSimulator(ros::NodeHandle *nh)
std::string odometry_topic
tf::StampedTransform odom_trans