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. | |
IdealMotionController (const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, ros::NodeHandle &n, const std::string &name, const stdr_msgs::KinematicMsg params) | |
Default constructor. | |
~IdealMotionController (void) | |
Default destructor. |
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.
void stdr_robot::IdealMotionController::calculateMotion | ( | const ros::TimerEvent & | event | ) | [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.