#include <reem_diffdrive_plugin.h>
Public Member Functions | |
| DiffDrivePlugin () | |
| ~DiffDrivePlugin () | |
Protected Member Functions | |
| virtual void | Load (physics::ModelPtr _parent, sdf::ElementPtr _sdf) | 
| virtual void | Update () | 
Private Member Functions | |
| void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg) | 
| void | GetPositionCmd () | 
| void | publishOdometry () | 
| void | QueueThread () | 
| void | writePositionData () | 
Private Attributes | |
| bool | alive_ | 
| boost::thread | callback_queue_thread_ | 
| std::string | cmdVelTopicName | 
| physics::JointPtr | joints [2] | 
| std::string | leftJointName | 
| boost::mutex | lock | 
| nav_msgs::Odometry | odom_ | 
| double | odomPose [3] | 
| std::string | odomTopicName | 
| double | odomVel [3] | 
| physics::ModelPtr | parent | 
| physics::PhysicsEnginePtr | physicsEngine | 
| ros::Publisher | pub_ | 
| ros::CallbackQueue | queue_ | 
| std::string | rightJointName | 
| std::string | robotNamespace | 
| ros::NodeHandle * | rosnode_ | 
| double | rot_ | 
| ros::Subscriber | sub_ | 
| std::string | tf_prefix_ | 
| double | torque | 
| tf::TransformBroadcaster * | transform_broadcaster_ | 
| event::ConnectionPtr | updateConnection | 
| double | wheelDiameter | 
| double | wheelSeparation | 
| double | wheelSpeed [2] | 
| physics::WorldPtr | world | 
| double | x_ | 
Definition at line 54 of file reem_diffdrive_plugin.h.
Definition at line 34 of file reem_diffdrive_plugin.cpp.
Definition at line 38 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::cmdVelCallback | ( | const geometry_msgs::Twist::ConstPtr & | cmd_msg | ) |  [private] | 
        
Definition at line 234 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::GetPositionCmd | ( | ) |  [private] | 
        
Definition at line 217 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::Load | ( | physics::ModelPtr | _parent, | 
| sdf::ElementPtr | _sdf | ||
| ) |  [protected, virtual] | 
        
Definition at line 51 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::publishOdometry | ( | ) |  [private] | 
        
Definition at line 254 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::QueueThread | ( | ) |  [private] | 
        
Definition at line 244 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::Update | ( | ) |  [protected, virtual] | 
        
Definition at line 177 of file reem_diffdrive_plugin.cpp.
| void gazebo::DiffDrivePlugin::writePositionData | ( | ) |  [private] | 
        
Definition at line 307 of file reem_diffdrive_plugin.cpp.
bool gazebo::DiffDrivePlugin::alive_ [private] | 
        
Definition at line 113 of file reem_diffdrive_plugin.h.
boost::thread gazebo::DiffDrivePlugin::callback_queue_thread_ [private] | 
        
Definition at line 105 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::cmdVelTopicName [private] | 
        
Definition at line 100 of file reem_diffdrive_plugin.h.
physics::JointPtr gazebo::DiffDrivePlugin::joints[2] [private] | 
        
Definition at line 86 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::leftJointName [private] | 
        
Definition at line 75 of file reem_diffdrive_plugin.h.
boost::mutex gazebo::DiffDrivePlugin::lock [private] | 
        
Definition at line 97 of file reem_diffdrive_plugin.h.
nav_msgs::Odometry gazebo::DiffDrivePlugin::odom_ [private] | 
        
Definition at line 94 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::odomPose[3] [private] | 
        
Definition at line 83 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::odomTopicName [private] | 
        
Definition at line 101 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::odomVel[3] [private] | 
        
Definition at line 84 of file reem_diffdrive_plugin.h.
physics::ModelPtr gazebo::DiffDrivePlugin::parent [private] | 
        
Definition at line 72 of file reem_diffdrive_plugin.h.
physics::PhysicsEnginePtr gazebo::DiffDrivePlugin::physicsEngine [private] | 
        
Definition at line 87 of file reem_diffdrive_plugin.h.
ros::Publisher gazebo::DiffDrivePlugin::pub_ [private] | 
        
Definition at line 91 of file reem_diffdrive_plugin.h.
Definition at line 104 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::rightJointName [private] | 
        
Definition at line 76 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::robotNamespace [private] | 
        
Definition at line 99 of file reem_diffdrive_plugin.h.
ros::NodeHandle* gazebo::DiffDrivePlugin::rosnode_ [private] | 
        
Definition at line 90 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::rot_ [private] | 
        
Definition at line 112 of file reem_diffdrive_plugin.h.
ros::Subscriber gazebo::DiffDrivePlugin::sub_ [private] | 
        
Definition at line 92 of file reem_diffdrive_plugin.h.
std::string gazebo::DiffDrivePlugin::tf_prefix_ [private] | 
        
Definition at line 95 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::torque [private] | 
        
Definition at line 80 of file reem_diffdrive_plugin.h.
Definition at line 93 of file reem_diffdrive_plugin.h.
Definition at line 73 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::wheelDiameter [private] | 
        
Definition at line 79 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::wheelSeparation [private] | 
        
Definition at line 78 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::wheelSpeed[2] [private] | 
        
Definition at line 81 of file reem_diffdrive_plugin.h.
physics::WorldPtr gazebo::DiffDrivePlugin::world [private] | 
        
Definition at line 71 of file reem_diffdrive_plugin.h.
double gazebo::DiffDrivePlugin::x_ [private] | 
        
Definition at line 111 of file reem_diffdrive_plugin.h.