Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
stdr_robot::MotionController Class Referenceabstract

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

#include <motion_controller_base.h>

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

Public Member Functions

virtual void calculateMotion (const ros::TimerEvent &event)=0
 Pure virtual function - Calculates the motion - updates the robot pose. More...
 
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...
 

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. More...
 

Protected Attributes

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...
 

Detailed Description

Abstract class that provides motion controller abstraction.

Definition at line 44 of file motion_controller_base.h.

Constructor & Destructor Documentation

virtual stdr_robot::MotionController::~MotionController ( void  )
inlinevirtual

Default desctructor.

Returns
void

Definition at line 161 of file motion_controller_base.h.

stdr_robot::MotionController::MotionController ( const geometry_msgs::Pose2D &  pose,
tf::TransformBroadcaster tf,
const std::string &  name,
ros::NodeHandle n,
const stdr_msgs::KinematicMsg  params 
)
inlineprotected

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 191 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::OmniMotionController, and 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 132 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 153 of file motion_controller_base.h.

float stdr_robot::MotionController::sampleNormal ( float  sigma)
inline

Approaches a normal distribution sampling.

Returns
float source: Sebastian Thrun, Probabilistic Robotics

Definition at line 170 of file motion_controller_base.h.

virtual void stdr_robot::MotionController::sampleVelocities ( void  )
inlinevirtual

Virtual function - Add noise to velocity commands.

Parameters
msg[geometry_msgs::Twist&] The velocity command
Returns
void The formulas used are:
  • u_x' = u_x + Sample(a_ux_ux * u_x^2 + a_ux_uy * u_y^2 + a_ux_w * w^2)
  • u_y' = u_y + Sample(a_uy_ux * u_x^2 + a_uy_uy * u_y^2 + a_uy_w * w^2)
  • w' = w + Sample(a_w_ux * u_x^2 + a_w_uy * u_y^2 + a_w_w * w^2)
  • g' = Sample(a_g_ux * u_x^2 + a_g_uy * u_y^2 + a_g_w * w^2) Then w' is used as such (depending on the model): theta' = theta + (w' + g') * Dt Sample(b^2) produces samples from a normal distribution with variance equal to b^2.

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.

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

Definition at line 142 of file motion_controller_base.h.

virtual void stdr_robot::MotionController::stop ( void  )
inlinevirtual

Virtual function - Stops the robot.

Returns
void

Definition at line 111 of file motion_controller_base.h.

virtual void stdr_robot::MotionController::velocityCallback ( const geometry_msgs::Twist &  msg)
inlinevirtual

Virtual function - Callback for velocity commands.

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

Definition at line 53 of file motion_controller_base.h.

Member Data Documentation

ros::Timer stdr_robot::MotionController::_calcTimer
protected

Broadcaster of the robot tf transform.

Definition at line 222 of file motion_controller_base.h.

geometry_msgs::Twist stdr_robot::MotionController::_currentTwist
protected

The kinematic model parameters.

Definition at line 228 of file motion_controller_base.h.

ros::Duration stdr_robot::MotionController::_freq
protected

ROS timer for generating motion calculation events.

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

geometry_msgs::Pose2D stdr_robot::MotionController::_pose
protected

Current motion command.

Definition at line 226 of file motion_controller_base.h.

tf::TransformBroadcaster& stdr_robot::MotionController::_tfBroadcaster
protected

Robot pose message.

Definition at line 224 of file motion_controller_base.h.

ros::Subscriber stdr_robot::MotionController::_velocitySubscrider
protected

Frequency of motion calculation.

Definition at line 218 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 Mon Jun 10 2019 15:15:10