25 #ifndef GAZEBO_ROS_PLANAR_MOVE_HH 26 #define GAZEBO_ROS_PLANAR_MOVE_HH 28 #include <boost/bind.hpp> 29 #include <boost/thread.hpp> 32 #include <gazebo/common/common.hh> 33 #include <gazebo/physics/physics.hh> 36 #include <geometry_msgs/Twist.h> 37 #include <nav_msgs/OccupancyGrid.h> 38 #include <nav_msgs/Odometry.h> 52 void Load(physics::ModelPtr parent, sdf::ElementPtr sdf);
86 void cmdVelCallback(
const geometry_msgs::Twist::ConstPtr& cmd_msg);
boost::shared_ptr< ros::NodeHandle > rosnode_
ignition::math::Pose3d last_odom_pose_
void publishOdometry(double step_time)
ros::CallbackQueue queue_
boost::thread callback_queue_thread_
virtual void UpdateChild()
physics::ModelPtr parent_
void Load(physics::ModelPtr parent, sdf::ElementPtr sdf)
void cmdVelCallback(const geometry_msgs::Twist::ConstPtr &cmd_msg)
event::ConnectionPtr update_connection_
std::string odometry_frame_
std::string robot_base_frame_
common::Time last_odom_publish_time_
ros::Publisher odometry_pub_
boost::shared_ptr< tf::TransformBroadcaster > transform_broadcaster_
bool enable_y_axis_
Enable Y-axis movement.
std::string odometry_topic_
std::string command_topic_
std::string robot_namespace_