#include <teo_plugin.h>
Public Member Functions | |
TeoPlugin (Entity *parent) | |
virtual | ~TeoPlugin () |
Protected Member Functions | |
virtual void | FiniChild () |
virtual void | InitChild () |
virtual void | LoadChild (XMLConfigNode *node) |
void | ResetChild () |
virtual void | UpdateChild () |
Private Member Functions | |
void | cmdVelCallback (const geometry_msgs::Twist::ConstPtr &cmd_msg) |
void | publish_odometry () |
void | QueueThread () |
void | write_position_data () |
Private Attributes | |
bool | alive_ |
ParamT< std::string > * | blNameP |
ParamT< std::string > * | brNameP |
boost::thread * | callback_queue_thread_ |
bool | enable_motors |
ParamT< std::string > * | flNameP |
ParamT< std::string > * | frNameP |
Joint * | joints_ [4] |
boost::mutex | lock |
nav_msgs::Odometry | odom_ |
float | odomPose [3] |
float | odomVel [3] |
Model * | parent_ |
libgazebo::PositionIface * | pos_iface_ |
float | previous_displ_ |
Time | prevUpdateTime_ |
ros::Publisher | pub_ |
ros::CallbackQueue | queue_ |
std::string | robotNamespace |
ParamT< std::string > * | robotNamespaceP |
ros::NodeHandle * | rosnode_ |
float | rot_z_ |
ros::Subscriber | sub_ |
std::string | tf_prefix_ |
std::string | topicName |
ParamT< std::string > * | topicNameP |
tf::TransformBroadcaster * | transform_broadcaster_ |
float | vel_x_ |
Definition at line 54 of file teo_plugin.h.
TeoPlugin::TeoPlugin | ( | Entity * | parent | ) |
Definition at line 60 of file teo_plugin.cpp.
TeoPlugin::~TeoPlugin | ( | ) | [virtual] |
Definition at line 85 of file teo_plugin.cpp.
void TeoPlugin::cmdVelCallback | ( | const geometry_msgs::Twist::ConstPtr & | cmd_msg | ) | [private] |
Definition at line 262 of file teo_plugin.cpp.
void TeoPlugin::FiniChild | ( | ) | [protected, virtual] |
Definition at line 250 of file teo_plugin.cpp.
void TeoPlugin::InitChild | ( | ) | [protected, virtual] |
Definition at line 144 of file teo_plugin.cpp.
void TeoPlugin::LoadChild | ( | XMLConfigNode * | node | ) | [protected, virtual] |
Definition at line 99 of file teo_plugin.cpp.
void TeoPlugin::publish_odometry | ( | ) | [private] |
Definition at line 287 of file teo_plugin.cpp.
void TeoPlugin::QueueThread | ( | ) | [private] |
Definition at line 275 of file teo_plugin.cpp.
void TeoPlugin::ResetChild | ( | ) | [protected] |
Definition at line 160 of file teo_plugin.cpp.
void TeoPlugin::UpdateChild | ( | ) | [protected, virtual] |
Definition at line 174 of file teo_plugin.cpp.
void TeoPlugin::write_position_data | ( | ) | [private] |
Definition at line 332 of file teo_plugin.cpp.
bool gazebo::TeoPlugin::alive_ [private] |
Definition at line 117 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::blNameP [private] |
Definition at line 101 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::brNameP [private] |
Definition at line 100 of file teo_plugin.h.
boost::thread* gazebo::TeoPlugin::callback_queue_thread_ [private] |
Definition at line 108 of file teo_plugin.h.
bool gazebo::TeoPlugin::enable_motors [private] |
Definition at line 84 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::flNameP [private] |
Definition at line 99 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::frNameP [private] |
Definition at line 98 of file teo_plugin.h.
Joint* gazebo::TeoPlugin::joints_[4] [private] |
Definition at line 76 of file teo_plugin.h.
boost::mutex gazebo::TeoPlugin::lock [private] |
Definition at line 94 of file teo_plugin.h.
nav_msgs::Odometry gazebo::TeoPlugin::odom_ [private] |
Definition at line 91 of file teo_plugin.h.
float gazebo::TeoPlugin::odomPose[3] [private] |
Definition at line 81 of file teo_plugin.h.
float gazebo::TeoPlugin::odomVel[3] [private] |
Definition at line 82 of file teo_plugin.h.
Model* gazebo::TeoPlugin::parent_ [private] |
Definition at line 74 of file teo_plugin.h.
libgazebo::PositionIface* gazebo::TeoPlugin::pos_iface_ [private] |
Definition at line 73 of file teo_plugin.h.
float gazebo::TeoPlugin::previous_displ_ [private] |
Definition at line 116 of file teo_plugin.h.
Time gazebo::TeoPlugin::prevUpdateTime_ [private] |
Definition at line 79 of file teo_plugin.h.
ros::Publisher gazebo::TeoPlugin::pub_ [private] |
Definition at line 88 of file teo_plugin.h.
ros::CallbackQueue gazebo::TeoPlugin::queue_ [private] |
Definition at line 107 of file teo_plugin.h.
std::string gazebo::TeoPlugin::robotNamespace [private] |
Definition at line 103 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::robotNamespaceP [private] |
Definition at line 96 of file teo_plugin.h.
ros::NodeHandle* gazebo::TeoPlugin::rosnode_ [private] |
Definition at line 87 of file teo_plugin.h.
float gazebo::TeoPlugin::rot_z_ [private] |
Definition at line 115 of file teo_plugin.h.
ros::Subscriber gazebo::TeoPlugin::sub_ [private] |
Definition at line 89 of file teo_plugin.h.
std::string gazebo::TeoPlugin::tf_prefix_ [private] |
Definition at line 92 of file teo_plugin.h.
std::string gazebo::TeoPlugin::topicName [private] |
Definition at line 104 of file teo_plugin.h.
ParamT<std::string>* gazebo::TeoPlugin::topicNameP [private] |
Definition at line 97 of file teo_plugin.h.
Definition at line 90 of file teo_plugin.h.
float gazebo::TeoPlugin::vel_x_ [private] |
Definition at line 114 of file teo_plugin.h.