Abstract class that provides motion controller abstraction. More...
#include <motion_controller_base.h>

Public Member Functions | |
| virtual void | calculateMotion (const ros::TimerEvent &event)=0 |
| Pure virtual function - Calculates the motion - updates the robot pose. | |
| geometry_msgs::Pose2D | getPose (void) |
| Returns the pose calculated by the motion controller. | |
| geometry_msgs::Twist | getVelocity () |
| Get the current velocity of the motion controller. | |
| float | sampleNormal (float sigma) |
| Approaches a normal distribution sampling. | |
| virtual void | sampleVelocities (void) |
| Virtual function - Add noise to velocity commands. | |
| void | setPose (geometry_msgs::Pose2D new_pose) |
| Sets the initial pose of the motion controller. | |
| virtual void | stop (void) |
| Virtual function - Stops the robot. | |
| virtual void | velocityCallback (const geometry_msgs::Twist &msg) |
| Virtual function - Callback for velocity commands. | |
| virtual | ~MotionController (void) |
| Default desctructor. | |
Protected Member Functions | |
| MotionController (const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, const std::string &name, ros::NodeHandle &n, const stdr_msgs::KinematicMsg params) | |
| Default constructor. | |
Protected Attributes | |
| ros::Timer | _calcTimer |
| Broadcaster of the robot tf transform. | |
| geometry_msgs::Twist | _currentTwist |
| The kinematic model parameters. | |
| ros::Duration | _freq |
| ROS timer for generating motion calculation events. | |
| stdr_msgs::KinematicMsg | _motion_parameters |
| const std::string & | _namespace |
| < The base of the frame_id | |
| geometry_msgs::Pose2D | _pose |
| Current motion command. | |
| tf::TransformBroadcaster & | _tfBroadcaster |
| Robot pose message. | |
| ros::Subscriber | _velocitySubscrider |
| Frequency of motion calculation. | |
Abstract class that provides motion controller abstraction.
Definition at line 44 of file motion_controller_base.h.
| virtual stdr_robot::MotionController::~MotionController | ( | void | ) | [inline, virtual] |
| stdr_robot::MotionController::MotionController | ( | const geometry_msgs::Pose2D & | pose, |
| tf::TransformBroadcaster & | tf, | ||
| const std::string & | name, | ||
| ros::NodeHandle & | n, | ||
| const stdr_msgs::KinematicMsg | params | ||
| ) | [inline, protected] |
Default constructor.
| pose | [const geometry_msgs::Pose2D&] The robot pose |
| tf | [tf::TransformBroadcaster&] A ROS tf broadcaster |
| name | [const std::string&] The robot frame id |
Definition at line 191 of file motion_controller_base.h.
| virtual void stdr_robot::MotionController::calculateMotion | ( | const ros::TimerEvent & | event | ) | [pure virtual] |
Pure virtual function - Calculates the motion - updates the robot pose.
| event | [const ros::TimerEvent&] A ROS timer event |
Implemented in stdr_robot::OmniMotionController, and stdr_robot::IdealMotionController.
| geometry_msgs::Pose2D stdr_robot::MotionController::getPose | ( | void | ) | [inline] |
Returns the pose calculated by the motion controller.
Definition at line 132 of file motion_controller_base.h.
| geometry_msgs::Twist stdr_robot::MotionController::getVelocity | ( | ) | [inline] |
Get the current velocity of the motion controller.
Definition at line 153 of file motion_controller_base.h.
| float stdr_robot::MotionController::sampleNormal | ( | float | sigma | ) | [inline] |
Approaches a normal distribution sampling.
Definition at line 170 of file motion_controller_base.h.
| virtual void stdr_robot::MotionController::sampleVelocities | ( | void | ) | [inline, virtual] |
Virtual function - Add noise to velocity commands.
| msg | [geometry_msgs::Twist&] The velocity command |
Definition at line 75 of file motion_controller_base.h.
| void stdr_robot::MotionController::setPose | ( | geometry_msgs::Pose2D | new_pose | ) | [inline] |
Sets the initial pose of the motion controller.
| new_pose | [geometry_msgs::Pose2D] The new pose |
Definition at line 142 of file motion_controller_base.h.
| virtual void stdr_robot::MotionController::stop | ( | void | ) | [inline, virtual] |
Virtual function - Stops the robot.
Definition at line 111 of file motion_controller_base.h.
| virtual void stdr_robot::MotionController::velocityCallback | ( | const geometry_msgs::Twist & | msg | ) | [inline, virtual] |
Virtual function - Callback for velocity commands.
| msg | [const geometry_msgs::Twist&] The velocity command |
Definition at line 53 of file motion_controller_base.h.
ros::Timer stdr_robot::MotionController::_calcTimer [protected] |
Broadcaster of the robot tf transform.
Definition at line 223 of file motion_controller_base.h.
geometry_msgs::Twist stdr_robot::MotionController::_currentTwist [protected] |
The kinematic model parameters.
Definition at line 229 of file motion_controller_base.h.
ros::Duration stdr_robot::MotionController::_freq [protected] |
ROS timer for generating motion calculation events.
Definition at line 221 of file motion_controller_base.h.
stdr_msgs::KinematicMsg stdr_robot::MotionController::_motion_parameters [protected] |
Definition at line 230 of file motion_controller_base.h.
const std::string& stdr_robot::MotionController::_namespace [protected] |
< The base of the frame_id
ROS subscriber to the velocity topic
Definition at line 217 of file motion_controller_base.h.
geometry_msgs::Pose2D stdr_robot::MotionController::_pose [protected] |
Current motion command.
Definition at line 227 of file motion_controller_base.h.
Robot pose message.
Definition at line 225 of file motion_controller_base.h.
Frequency of motion calculation.
Definition at line 219 of file motion_controller_base.h.