Public Member Functions | Protected Member Functions | Protected Attributes
stdr_robot::MotionController Class Reference

Abstract class that provides motion controller abstraction. More...

#include <motion_controller_base.h>

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

List of all members.

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.
void setPose (geometry_msgs::Pose2D new_pose)
 Sets the initial pose of the motion controller.
virtual void stop (void)=0
 Pure virtual function - Stops the robot.
virtual void velocityCallback (const geometry_msgs::Twist &msg)=0
 Pure 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)
 Default constructor.

Protected Attributes

ros::Timer _calcTimer
 Broadcaster of the robot tf transform.
geometry_msgs::Twist _currentTwist
ros::Duration _freq
 ROS timer for generating motion calculation events.
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.

Detailed Description

Abstract class that provides motion controller abstraction.

Definition at line 40 of file motion_controller_base.h.


Constructor & Destructor Documentation

virtual stdr_robot::MotionController::~MotionController ( void  ) [inline, virtual]

Default desctructor.

Returns:
void

Definition at line 97 of file motion_controller_base.h.

stdr_robot::MotionController::MotionController ( const geometry_msgs::Pose2D &  pose,
tf::TransformBroadcaster tf,
const std::string &  name 
) [inline, protected]

Default constructor.

Parameters:
pose[const geometry_msgs::Pose2D&] The robot pose
tf[tf::TransformBroadcaster&] A ROS tf broadcaster
name[const std::string&] The robot frame id
Returns:
void

Definition at line 110 of file motion_controller_base.h.


Member Function Documentation

virtual void stdr_robot::MotionController::calculateMotion ( const ros::TimerEvent event) [pure virtual]

Pure virtual function - Calculates the motion - updates the robot pose.

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

Implemented in stdr_robot::IdealMotionController.

geometry_msgs::Pose2D stdr_robot::MotionController::getPose ( void  ) [inline]

Returns the pose calculated by the motion controller.

Returns:
geometry_msgs::Pose2D

Definition at line 68 of file motion_controller_base.h.

geometry_msgs::Twist stdr_robot::MotionController::getVelocity ( ) [inline]

Get the current velocity of the motion controller.

Returns:
geometry_msgs::Twist

Definition at line 89 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.

Parameters:
new_pose[geometry_msgs::Pose2D] The new pose
Returns:
void

Definition at line 78 of file motion_controller_base.h.

virtual void stdr_robot::MotionController::stop ( void  ) [pure virtual]

Pure virtual function - Stops the robot.

Returns:
void

Implemented in stdr_robot::IdealMotionController.

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

Pure virtual function - Callback for velocity commands.

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

Implemented in stdr_robot::IdealMotionController.


Member Data Documentation

Broadcaster of the robot tf transform.

Definition at line 130 of file motion_controller_base.h.

geometry_msgs::Twist stdr_robot::MotionController::_currentTwist [protected]

Definition at line 135 of file motion_controller_base.h.

ROS timer for generating motion calculation events.

Definition at line 128 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 124 of file motion_controller_base.h.

geometry_msgs::Pose2D stdr_robot::MotionController::_pose [protected]

Current motion command.

Definition at line 134 of file motion_controller_base.h.

Robot pose message.

Definition at line 132 of file motion_controller_base.h.

Frequency of motion calculation.

Definition at line 126 of file motion_controller_base.h.


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


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