#include <diffdrive_plugin_multi_wheel.h>
Public Member Functions | |
GazeboRosDiffDriveMultiWheel () | |
void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) |
~GazeboRosDiffDriveMultiWheel () | |
Protected Member Functions | |
virtual void | FiniChild () |
virtual void | UpdateChild () |
Private Member Functions | |
void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg) |
void | getWheelVelocities () |
void | publishOdometry (double step_time) |
void | QueueThread () |
Private Attributes | |
bool | alive_ |
boost::thread | callback_queue_thread_ |
ros::Subscriber | cmd_vel_subscriber_ |
std::string | command_topic_ |
std::vector< std::string > | joint_names_ [2] |
std::vector< physics::JointPtr > | joints_ [2] |
common::Time | last_update_time_ |
boost::mutex | lock |
nav_msgs::Odometry | odom_ |
std::string | odometry_frame_ |
ros::Publisher | odometry_publisher_ |
std::string | odometry_topic_ |
physics::ModelPtr | parent |
bool | publish_odometry_msg_ |
bool | publish_odometry_tf_ |
ros::CallbackQueue | queue_ |
std::string | robot_base_frame_ |
std::string | robot_namespace_ |
ros::NodeHandle * | rosnode_ |
double | rot_ |
std::string | tf_prefix_ |
double | torque |
tf::TransformBroadcaster * | transform_broadcaster_ |
event::ConnectionPtr | update_connection_ |
double | update_period_ |
double | update_rate_ |
double | wheel_diameter_ |
double | wheel_separation_ |
double | wheel_speed_ [2] |
physics::WorldPtr | world |
double | x_ |
Definition at line 104 of file diffdrive_plugin_multi_wheel.h.
Definition at line 101 of file diffdrive_plugin_multi_wheel.cpp.
Definition at line 104 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::cmdVelCallback | ( | const geometry_msgs::Twist::ConstPtr & | cmd_msg | ) | [private] |
Definition at line 336 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::FiniChild | ( | ) | [protected, virtual] |
Definition at line 318 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::getWheelVelocities | ( | ) | [private] |
Definition at line 326 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::Load | ( | physics::ModelPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Definition at line 110 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::publishOdometry | ( | double | step_time | ) | [private] |
Definition at line 352 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::QueueThread | ( | ) | [private] |
Definition at line 344 of file diffdrive_plugin_multi_wheel.cpp.
void gazebo::GazeboRosDiffDriveMultiWheel::UpdateChild | ( | ) | [protected, virtual] |
Definition at line 291 of file diffdrive_plugin_multi_wheel.cpp.
bool gazebo::GazeboRosDiffDriveMultiWheel::alive_ [private] |
Definition at line 158 of file diffdrive_plugin_multi_wheel.h.
boost::thread gazebo::GazeboRosDiffDriveMultiWheel::callback_queue_thread_ [private] |
Definition at line 150 of file diffdrive_plugin_multi_wheel.h.
Definition at line 135 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::command_topic_ [private] |
Definition at line 143 of file diffdrive_plugin_multi_wheel.h.
std::vector<std::string> gazebo::GazeboRosDiffDriveMultiWheel::joint_names_[2] [private] |
Definition at line 123 of file diffdrive_plugin_multi_wheel.h.
std::vector<physics::JointPtr> gazebo::GazeboRosDiffDriveMultiWheel::joints_[2] [private] |
Definition at line 130 of file diffdrive_plugin_multi_wheel.h.
common::Time gazebo::GazeboRosDiffDriveMultiWheel::last_update_time_ [private] |
Definition at line 163 of file diffdrive_plugin_multi_wheel.h.
boost::mutex gazebo::GazeboRosDiffDriveMultiWheel::lock [private] |
Definition at line 140 of file diffdrive_plugin_multi_wheel.h.
nav_msgs::Odometry gazebo::GazeboRosDiffDriveMultiWheel::odom_ [private] |
Definition at line 137 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::odometry_frame_ [private] |
Definition at line 145 of file diffdrive_plugin_multi_wheel.h.
Definition at line 134 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::odometry_topic_ [private] |
Definition at line 144 of file diffdrive_plugin_multi_wheel.h.
physics::ModelPtr gazebo::GazeboRosDiffDriveMultiWheel::parent [private] |
Definition at line 120 of file diffdrive_plugin_multi_wheel.h.
bool gazebo::GazeboRosDiffDriveMultiWheel::publish_odometry_msg_ [private] |
Definition at line 166 of file diffdrive_plugin_multi_wheel.h.
bool gazebo::GazeboRosDiffDriveMultiWheel::publish_odometry_tf_ [private] |
Definition at line 165 of file diffdrive_plugin_multi_wheel.h.
Definition at line 149 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::robot_base_frame_ [private] |
Definition at line 146 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::robot_namespace_ [private] |
Definition at line 142 of file diffdrive_plugin_multi_wheel.h.
Definition at line 133 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::rot_ [private] |
Definition at line 157 of file diffdrive_plugin_multi_wheel.h.
std::string gazebo::GazeboRosDiffDriveMultiWheel::tf_prefix_ [private] |
Definition at line 138 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::torque [private] |
Definition at line 127 of file diffdrive_plugin_multi_wheel.h.
Definition at line 136 of file diffdrive_plugin_multi_wheel.h.
Definition at line 121 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::update_period_ [private] |
Definition at line 162 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::update_rate_ [private] |
Definition at line 161 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::wheel_diameter_ [private] |
Definition at line 126 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::wheel_separation_ [private] |
Definition at line 125 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::wheel_speed_[2] [private] |
Definition at line 128 of file diffdrive_plugin_multi_wheel.h.
physics::WorldPtr gazebo::GazeboRosDiffDriveMultiWheel::world [private] |
Definition at line 119 of file diffdrive_plugin_multi_wheel.h.
double gazebo::GazeboRosDiffDriveMultiWheel::x_ [private] |
Definition at line 156 of file diffdrive_plugin_multi_wheel.h.