Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
gazebo::DiffDrivePlugin6W Class Reference

#include <diffdrive_plugin_6w.h>

Inheritance diagram for gazebo::DiffDrivePlugin6W:
Inheritance graph
[legend]

Public Member Functions

 DiffDrivePlugin6W ()
 
virtual ~DiffDrivePlugin6W ()
 

Protected Member Functions

virtual void Load (physics::ModelPtr _model, sdf::ElementPtr _sdf)
 
virtual void Reset ()
 
virtual void Update ()
 

Private Member Functions

void cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg)
 
void GetPositionCmd ()
 
void publish_odometry ()
 
void QueueThread ()
 

Private Attributes

bool alive_
 
boost::thread callback_queue_thread_
 
bool enableMotors
 
physics::JointPtr joints [6]
 
physics::LinkPtr link
 
std::string link_name_
 
boost::mutex lock
 
std::string namespace_
 
nav_msgs::Odometry odom_
 
float odomPose [3]
 
float odomVel [3]
 
common::Time prevUpdateTime
 
ros::Publisher pub_
 
ros::CallbackQueue queue_
 
ros::NodeHandlerosnode_
 
float rot_
 
ros::Subscriber sub_
 
std::string tf_prefix_
 
std::string topic_
 
float torque
 
tf::TransformBroadcastertransform_broadcaster_
 
event::ConnectionPtr updateConnection
 
float wheelDiam
 
float wheelSep
 
float wheelSpeed [2]
 
physics::WorldPtr world
 
float x_
 

Detailed Description

Definition at line 51 of file diffdrive_plugin_6w.h.

Constructor & Destructor Documentation

gazebo::DiffDrivePlugin6W::DiffDrivePlugin6W ( )

Definition at line 63 of file diffdrive_plugin_6w.cpp.

gazebo::DiffDrivePlugin6W::~DiffDrivePlugin6W ( )
virtual

Definition at line 68 of file diffdrive_plugin_6w.cpp.

Member Function Documentation

void gazebo::DiffDrivePlugin6W::cmdVelCallback ( const geometry_msgs::Twist::ConstPtr &  cmd_msg)
private

Definition at line 292 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::GetPositionCmd ( )
private

Definition at line 269 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::Load ( physics::ModelPtr  _model,
sdf::ElementPtr  _sdf 
)
protectedvirtual

Definition at line 82 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::publish_odometry ( )
private

Definition at line 319 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::QueueThread ( )
private

Definition at line 307 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::Reset ( )
protectedvirtual

Definition at line 172 of file diffdrive_plugin_6w.cpp.

void gazebo::DiffDrivePlugin6W::Update ( )
protectedvirtual

Definition at line 201 of file diffdrive_plugin_6w.cpp.

Member Data Documentation

bool gazebo::DiffDrivePlugin6W::alive_
private

Definition at line 107 of file diffdrive_plugin_6w.h.

boost::thread gazebo::DiffDrivePlugin6W::callback_queue_thread_
private

Definition at line 99 of file diffdrive_plugin_6w.h.

bool gazebo::DiffDrivePlugin6W::enableMotors
private

Definition at line 79 of file diffdrive_plugin_6w.h.

physics::JointPtr gazebo::DiffDrivePlugin6W::joints[6]
private

Definition at line 69 of file diffdrive_plugin_6w.h.

physics::LinkPtr gazebo::DiffDrivePlugin6W::link
private

Definition at line 67 of file diffdrive_plugin_6w.h.

std::string gazebo::DiffDrivePlugin6W::link_name_
private

Definition at line 95 of file diffdrive_plugin_6w.h.

boost::mutex gazebo::DiffDrivePlugin6W::lock
private

Definition at line 91 of file diffdrive_plugin_6w.h.

std::string gazebo::DiffDrivePlugin6W::namespace_
private

Definition at line 93 of file diffdrive_plugin_6w.h.

nav_msgs::Odometry gazebo::DiffDrivePlugin6W::odom_
private

Definition at line 88 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::odomPose[3]
private

Definition at line 80 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::odomVel[3]
private

Definition at line 81 of file diffdrive_plugin_6w.h.

common::Time gazebo::DiffDrivePlugin6W::prevUpdateTime
private

Definition at line 77 of file diffdrive_plugin_6w.h.

ros::Publisher gazebo::DiffDrivePlugin6W::pub_
private

Definition at line 85 of file diffdrive_plugin_6w.h.

ros::CallbackQueue gazebo::DiffDrivePlugin6W::queue_
private

Definition at line 98 of file diffdrive_plugin_6w.h.

ros::NodeHandle* gazebo::DiffDrivePlugin6W::rosnode_
private

Definition at line 84 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::rot_
private

Definition at line 106 of file diffdrive_plugin_6w.h.

ros::Subscriber gazebo::DiffDrivePlugin6W::sub_
private

Definition at line 86 of file diffdrive_plugin_6w.h.

std::string gazebo::DiffDrivePlugin6W::tf_prefix_
private

Definition at line 89 of file diffdrive_plugin_6w.h.

std::string gazebo::DiffDrivePlugin6W::topic_
private

Definition at line 94 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::torque
private

Definition at line 73 of file diffdrive_plugin_6w.h.

tf::TransformBroadcaster* gazebo::DiffDrivePlugin6W::transform_broadcaster_
private

Definition at line 87 of file diffdrive_plugin_6w.h.

event::ConnectionPtr gazebo::DiffDrivePlugin6W::updateConnection
private

Definition at line 110 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::wheelDiam
private

Definition at line 72 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::wheelSep
private

Definition at line 71 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::wheelSpeed[2]
private

Definition at line 74 of file diffdrive_plugin_6w.h.

physics::WorldPtr gazebo::DiffDrivePlugin6W::world
private

Definition at line 68 of file diffdrive_plugin_6w.h.

float gazebo::DiffDrivePlugin6W::x_
private

Definition at line 105 of file diffdrive_plugin_6w.h.


The documentation for this class was generated from the following files:


hector_gazebo_plugins
Author(s): Stefan Kohlbrecher , Johannes Meyer
autogenerated on Wed Jun 5 2019 22:40:23