#include <YouBotConfiguration.h>
Public Member Functions | |
YouBotBaseConfiguration () | |
Standard constructor. | |
virtual | ~YouBotBaseConfiguration () |
Standard destructor. | |
Public Attributes | |
ros::Subscriber | baseCommandSubscriber |
Receives Twist messages for the base. | |
std::string | baseID |
"Name" of the base. Typically derived from name of youBot configuration file. | |
ros::Publisher | baseJointStatePublisher |
Publishes JointState messages with angles/velocities for the wheels. | |
ros::Publisher | baseOdometryPublisher |
Publishes Odometry messages. | |
tf::TransformBroadcaster | odometryBroadcaster |
Publishes tf frames as odometry. | |
ros::ServiceServer | switchOffMotorsService |
Service to switch the motor off by setting the PWM value to zero. | |
ros::ServiceServer | switchONMotorsService |
Service to switch the motor ON by setting the velocity to zero. | |
std::vector< std::string > | wheelNames |
Joint names for the wheels. | |
youbot::YouBotBase * | youBotBase |
Handle to the base. |
Definition at line 60 of file YouBotConfiguration.h.
Standard constructor.
Definition at line 45 of file YouBotConfiguration.cpp.
Standard destructor.
Definition at line 71 of file YouBotConfiguration.cpp.
Receives Twist messages for the base.
Definition at line 82 of file YouBotConfiguration.h.
std::string youBot::YouBotBaseConfiguration::baseID |
"Name" of the base. Typically derived from name of youBot configuration file.
Definition at line 75 of file YouBotConfiguration.h.
Publishes JointState messages with angles/velocities for the wheels.
Definition at line 89 of file YouBotConfiguration.h.
Publishes Odometry messages.
Definition at line 86 of file YouBotConfiguration.h.
Publishes tf frames as odometry.
Definition at line 98 of file YouBotConfiguration.h.
Service to switch the motor off by setting the PWM value to zero.
Definition at line 92 of file YouBotConfiguration.h.
Service to switch the motor ON by setting the velocity to zero.
Definition at line 95 of file YouBotConfiguration.h.
std::vector<std::string> youBot::YouBotBaseConfiguration::wheelNames |
Joint names for the wheels.
Definition at line 78 of file YouBotConfiguration.h.
youbot::YouBotBase* youBot::YouBotBaseConfiguration::youBotBase |
Handle to the base.
Definition at line 71 of file YouBotConfiguration.h.