Public Member Functions
stdr_robot::IdealMotionController Class Reference

A class that provides motion controller implementation. Inherits publicly MotionController. More...

#include <ideal_motion_controller.h>

Inheritance diagram for stdr_robot::IdealMotionController:
Inheritance graph
[legend]

List of all members.

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)
 Default constructor.
void stop (void)
 Stops the robot.
void velocityCallback (const geometry_msgs::Twist &msg)
 Callback for velocity commands.
 ~IdealMotionController (void)
 Default destructor.

Detailed Description

A class that provides motion controller implementation. Inherits publicly MotionController.

Definition at line 38 of file ideal_motion_controller.h.


Constructor & Destructor Documentation

stdr_robot::IdealMotionController::IdealMotionController ( const geometry_msgs::Pose2D &  pose,
tf::TransformBroadcaster tf,
ros::NodeHandle n,
const std::string &  name 
)

Default constructor.

Parameters:
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
Returns:
void

Definition at line 34 of file ideal_motion_controller.cpp.

Default destructor.

Returns:
void

Definition at line 108 of file ideal_motion_controller.cpp.


Member Function Documentation

Calculates the motion - updates the robot pose.

Parameters:
event[const ros::TimerEvent&] A ROS timer event
Returns:
void

< updates _posePtr based on _currentTwist and time passed (event.last_real)

Implements stdr_robot::MotionController.

Definition at line 78 of file ideal_motion_controller.cpp.

void stdr_robot::IdealMotionController::stop ( void  ) [virtual]

Stops the robot.

Returns:
void

Implements stdr_robot::MotionController.

Definition at line 67 of file ideal_motion_controller.cpp.

void stdr_robot::IdealMotionController::velocityCallback ( const geometry_msgs::Twist &  msg) [virtual]

Callback for velocity commands.

Parameters:
msg[const geometry_msgs::Twist&] The velocity command
Returns:
void

Implements stdr_robot::MotionController.

Definition at line 58 of file ideal_motion_controller.cpp.


The documentation for this class was generated from the following files:


stdr_robot
Author(s): Manos Tsardoulias, Chris Zalidis, Aris Thallas
autogenerated on Wed Sep 2 2015 03:36:25