#include <husky_controller.h>
Public Member Functions | |
| DiffDrivePlugin (Entity *parent) | |
| virtual | ~DiffDrivePlugin () | 
Protected Member Functions | |
| virtual void | FiniChild () | 
| virtual void | InitChild () | 
| virtual void | LoadChild (XMLConfigNode *node) | 
| void | ResetChild () | 
| void | SaveChild (std::string &prefix, std::ostream &stream) | 
| virtual void | UpdateChild () | 
Private Member Functions | |
| void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg) | 
| void | GetPositionCmd () | 
| void | publish_odometry () | 
| void | QueueThread () | 
| void | write_position_data () | 
Private Attributes | |
| bool | alive_ | 
| ParamT< std::string > * | backLeftJointNameP | 
| ParamT< std::string > * | backRightJointNameP | 
| boost::thread * | callback_queue_thread_ | 
| bool | enableMotors | 
| ParamT< std::string > * | frontLeftJointNameP | 
| ParamT< std::string > * | frontRightJointNameP | 
| Joint * | joints [4] | 
| boost::mutex | lock | 
| nav_msgs::Odometry | odom_ | 
| float | odomPose [3] | 
| float | odomVel [3] | 
| Model * | parent_ | 
| PhysicsEngine * | physicsEngine | 
| libgazebo::PositionIface * | pos_iface_ | 
| Time | prevUpdateTime | 
| ros::Publisher | pub_ | 
| ros::CallbackQueue | queue_ | 
| std::string | robotNamespace | 
| ParamT< std::string > * | robotNamespaceP | 
| ros::NodeHandle * | rosnode_ | 
| float | rot_ | 
| ros::Subscriber | sub_ | 
| std::string | tf_prefix_ | 
| std::string | topicName | 
| ParamT< std::string > * | topicNameP | 
| ParamT< float > * | torqueP | 
| tf::TransformBroadcaster * | transform_broadcaster_ | 
| ParamT< float > * | wheelDiamP | 
| ParamT< float > * | wheelSepP | 
| float | wheelSpeed [2] | 
| float | x_ | 
Definition at line 55 of file husky_controller.h.
| DiffDrivePlugin::DiffDrivePlugin | ( | Entity * | parent | ) | 
Definition at line 60 of file husky_controller.cpp.
| DiffDrivePlugin::~DiffDrivePlugin | ( | ) |  [virtual] | 
        
Definition at line 94 of file husky_controller.cpp.
| void DiffDrivePlugin::cmdVelCallback | ( | const geometry_msgs::Twist::ConstPtr & | cmd_msg | ) |  [private] | 
        
Definition at line 308 of file husky_controller.cpp.
| void DiffDrivePlugin::FiniChild | ( | ) |  [protected, virtual] | 
        
Definition at line 275 of file husky_controller.cpp.
| void DiffDrivePlugin::GetPositionCmd | ( | ) |  [private] | 
        
Definition at line 288 of file husky_controller.cpp.
| void DiffDrivePlugin::InitChild | ( | ) |  [protected, virtual] | 
        
Definition at line 168 of file husky_controller.cpp.
| void DiffDrivePlugin::LoadChild | ( | XMLConfigNode * | node | ) |  [protected, virtual] | 
        
Definition at line 111 of file husky_controller.cpp.
| void DiffDrivePlugin::publish_odometry | ( | ) |  [private] | 
        
Definition at line 331 of file husky_controller.cpp.
| void DiffDrivePlugin::QueueThread | ( | ) |  [private] | 
        
Definition at line 320 of file husky_controller.cpp.
| void DiffDrivePlugin::ResetChild | ( | ) |  [protected] | 
        
Definition at line 195 of file husky_controller.cpp.
| void DiffDrivePlugin::SaveChild | ( | std::string & | prefix, | 
| std::ostream & | stream | ||
| ) |  [protected] | 
        
Definition at line 183 of file husky_controller.cpp.
| void DiffDrivePlugin::UpdateChild | ( | ) |  [protected, virtual] | 
        
Definition at line 208 of file husky_controller.cpp.
| void DiffDrivePlugin::write_position_data | ( | ) |  [private] | 
        
Definition at line 373 of file husky_controller.cpp.
bool gazebo::DiffDrivePlugin::alive_ [private] | 
        
Definition at line 121 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::backLeftJointNameP [private] | 
        
Definition at line 90 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::backRightJointNameP [private] | 
        
Definition at line 91 of file husky_controller.h.
boost::thread* gazebo::DiffDrivePlugin::callback_queue_thread_ [private] | 
        
Definition at line 113 of file husky_controller.h.
bool gazebo::DiffDrivePlugin::enableMotors [private] | 
        
Definition at line 84 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::frontLeftJointNameP [private] | 
        
Definition at line 92 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::frontRightJointNameP [private] | 
        
Definition at line 93 of file husky_controller.h.
Joint* gazebo::DiffDrivePlugin::joints[4] [private] | 
        
Definition at line 88 of file husky_controller.h.
boost::mutex gazebo::DiffDrivePlugin::lock [private] | 
        
Definition at line 103 of file husky_controller.h.
nav_msgs::Odometry gazebo::DiffDrivePlugin::odom_ [private] | 
        
Definition at line 100 of file husky_controller.h.
float gazebo::DiffDrivePlugin::odomPose[3] [private] | 
        
Definition at line 85 of file husky_controller.h.
float gazebo::DiffDrivePlugin::odomVel[3] [private] | 
        
Definition at line 86 of file husky_controller.h.
Model* gazebo::DiffDrivePlugin::parent_ [private] | 
        
Definition at line 75 of file husky_controller.h.
PhysicsEngine* gazebo::DiffDrivePlugin::physicsEngine [private] | 
        
Definition at line 89 of file husky_controller.h.
libgazebo::PositionIface* gazebo::DiffDrivePlugin::pos_iface_ [private] | 
        
Definition at line 74 of file husky_controller.h.
Time gazebo::DiffDrivePlugin::prevUpdateTime [private] | 
        
Definition at line 82 of file husky_controller.h.
ros::Publisher gazebo::DiffDrivePlugin::pub_ [private] | 
        
Definition at line 97 of file husky_controller.h.
Definition at line 112 of file husky_controller.h.
std::string gazebo::DiffDrivePlugin::robotNamespace [private] | 
        
Definition at line 106 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::robotNamespaceP [private] | 
        
Definition at line 105 of file husky_controller.h.
ros::NodeHandle* gazebo::DiffDrivePlugin::rosnode_ [private] | 
        
Definition at line 96 of file husky_controller.h.
float gazebo::DiffDrivePlugin::rot_ [private] | 
        
Definition at line 120 of file husky_controller.h.
ros::Subscriber gazebo::DiffDrivePlugin::sub_ [private] | 
        
Definition at line 98 of file husky_controller.h.
std::string gazebo::DiffDrivePlugin::tf_prefix_ [private] | 
        
Definition at line 101 of file husky_controller.h.
std::string gazebo::DiffDrivePlugin::topicName [private] | 
        
Definition at line 109 of file husky_controller.h.
ParamT<std::string>* gazebo::DiffDrivePlugin::topicNameP [private] | 
        
Definition at line 108 of file husky_controller.h.
ParamT<float>* gazebo::DiffDrivePlugin::torqueP [private] | 
        
Definition at line 78 of file husky_controller.h.
Definition at line 99 of file husky_controller.h.
ParamT<float>* gazebo::DiffDrivePlugin::wheelDiamP [private] | 
        
Definition at line 77 of file husky_controller.h.
ParamT<float>* gazebo::DiffDrivePlugin::wheelSepP [private] | 
        
Definition at line 76 of file husky_controller.h.
float gazebo::DiffDrivePlugin::wheelSpeed[2] [private] | 
        
Definition at line 79 of file husky_controller.h.
float gazebo::DiffDrivePlugin::x_ [private] | 
        
Definition at line 119 of file husky_controller.h.