A class that provides motion controller implementation. Inherits publicly MotionController. More...
#include <ideal_motion_controller.h>

Public Member Functions | |
| void | calculateMotion (const ros::TimerEvent &event) |
| Calculates the motion - updates the robot pose. More... | |
| IdealMotionController (const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, ros::NodeHandle &n, const std::string &name, const stdr_msgs::KinematicMsg params) | |
| Default constructor. More... | |
| ~IdealMotionController (void) | |
| Default destructor. More... | |
Public Member Functions inherited from stdr_robot::MotionController | |
| geometry_msgs::Pose2D | getPose (void) |
| Returns the pose calculated by the motion controller. More... | |
| geometry_msgs::Twist | getVelocity () |
| Get the current velocity of the motion controller. More... | |
| float | sampleNormal (float sigma) |
| Approaches a normal distribution sampling. More... | |
| virtual void | sampleVelocities (void) |
| Virtual function - Add noise to velocity commands. More... | |
| void | setPose (geometry_msgs::Pose2D new_pose) |
| Sets the initial pose of the motion controller. More... | |
| virtual void | stop (void) |
| Virtual function - Stops the robot. More... | |
| virtual void | velocityCallback (const geometry_msgs::Twist &msg) |
| Virtual function - Callback for velocity commands. More... | |
| virtual | ~MotionController (void) |
| Default desctructor. More... | |
Additional Inherited Members | |
Protected Member Functions inherited from stdr_robot::MotionController | |
| MotionController (const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, const std::string &name, ros::NodeHandle &n, const stdr_msgs::KinematicMsg params) | |
| Default constructor. More... | |
Protected Attributes inherited from stdr_robot::MotionController | |
| ros::Timer | _calcTimer |
| Broadcaster of the robot tf transform. More... | |
| geometry_msgs::Twist | _currentTwist |
| The kinematic model parameters. More... | |
| ros::Duration | _freq |
| ROS timer for generating motion calculation events. More... | |
| stdr_msgs::KinematicMsg | _motion_parameters |
| const std::string & | _namespace |
| < The base of the frame_id More... | |
| geometry_msgs::Pose2D | _pose |
| Current motion command. More... | |
| tf::TransformBroadcaster & | _tfBroadcaster |
| Robot pose message. More... | |
| ros::Subscriber | _velocitySubscrider |
| Frequency of motion calculation. More... | |
A class that provides motion controller implementation. Inherits publicly MotionController.
Definition at line 38 of file ideal_motion_controller.h.
| stdr_robot::IdealMotionController::IdealMotionController | ( | const geometry_msgs::Pose2D & | pose, |
| tf::TransformBroadcaster & | tf, | ||
| ros::NodeHandle & | n, | ||
| const std::string & | name, | ||
| const stdr_msgs::KinematicMsg | params | ||
| ) |
Default constructor.
| pose | [const geometry_msgs::Pose2D&] The robot pose |
| tf | [tf::TransformBroadcaster&] A ROS tf broadcaster |
| n | [ros::NodeHandle&] The ROS node handle |
| name | [const std::string&] The robot frame id |
Definition at line 34 of file ideal_motion_controller.cpp.
| stdr_robot::IdealMotionController::~IdealMotionController | ( | void | ) |
|
virtual |
Calculates the motion - updates the robot pose.
| event | [const ros::TimerEvent&] A ROS timer event |
< updates _posePtr based on _currentTwist and time passed (event.last_real)
Implements stdr_robot::MotionController.
Definition at line 53 of file ideal_motion_controller.cpp.