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