#include <diffdrive_plugin_6w.h>
|
virtual void | Load (physics::ModelPtr _model, sdf::ElementPtr _sdf) |
|
virtual void | Reset () |
|
virtual void | Update () |
|
Definition at line 58 of file diffdrive_plugin_6w.h.
gazebo::DiffDrivePlugin6W::DiffDrivePlugin6W |
( |
| ) |
|
gazebo::DiffDrivePlugin6W::~DiffDrivePlugin6W |
( |
| ) |
|
|
virtual |
void gazebo::DiffDrivePlugin6W::cmdVelCallback |
( |
const geometry_msgs::Twist::ConstPtr & |
cmd_msg | ) |
|
|
private |
void gazebo::DiffDrivePlugin6W::GetPositionCmd |
( |
| ) |
|
|
private |
void gazebo::DiffDrivePlugin6W::Load |
( |
physics::ModelPtr |
_model, |
|
|
sdf::ElementPtr |
_sdf |
|
) |
| |
|
protectedvirtual |
void gazebo::DiffDrivePlugin6W::publish_odometry |
( |
| ) |
|
|
private |
void gazebo::DiffDrivePlugin6W::QueueThread |
( |
| ) |
|
|
private |
void gazebo::DiffDrivePlugin6W::Reset |
( |
| ) |
|
|
protectedvirtual |
void gazebo::DiffDrivePlugin6W::Update |
( |
| ) |
|
|
protectedvirtual |
bool gazebo::DiffDrivePlugin6W::alive_ |
|
private |
boost::thread gazebo::DiffDrivePlugin6W::callback_queue_thread_ |
|
private |
bool gazebo::DiffDrivePlugin6W::enableMotors |
|
private |
physics::JointPtr gazebo::DiffDrivePlugin6W::joints[6] |
|
private |
physics::LinkPtr gazebo::DiffDrivePlugin6W::link |
|
private |
std::string gazebo::DiffDrivePlugin6W::link_name_ |
|
private |
boost::mutex gazebo::DiffDrivePlugin6W::lock |
|
private |
std::string gazebo::DiffDrivePlugin6W::namespace_ |
|
private |
nav_msgs::Odometry gazebo::DiffDrivePlugin6W::odom_ |
|
private |
float gazebo::DiffDrivePlugin6W::odomPose[3] |
|
private |
float gazebo::DiffDrivePlugin6W::odomVel[3] |
|
private |
common::Time gazebo::DiffDrivePlugin6W::prevUpdateTime |
|
private |
float gazebo::DiffDrivePlugin6W::rot_ |
|
private |
std::string gazebo::DiffDrivePlugin6W::tf_prefix_ |
|
private |
std::string gazebo::DiffDrivePlugin6W::topic_ |
|
private |
float gazebo::DiffDrivePlugin6W::torque |
|
private |
float gazebo::DiffDrivePlugin6W::wheelDiam |
|
private |
float gazebo::DiffDrivePlugin6W::wheelSep |
|
private |
float gazebo::DiffDrivePlugin6W::wheelSpeed[2] |
|
private |
physics::WorldPtr gazebo::DiffDrivePlugin6W::world |
|
private |
float gazebo::DiffDrivePlugin6W::x_ |
|
private |
The documentation for this class was generated from the following files: