Public Member Functions | List of all members
stdr_robot::OmniMotionController Class Reference

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

#include <omni_motion_controller.h>

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

Public Member Functions

void calculateMotion (const ros::TimerEvent &event)
 Calculates the motion - updates the robot pose. More...
 
 OmniMotionController (const geometry_msgs::Pose2D &pose, tf::TransformBroadcaster &tf, ros::NodeHandle &n, const std::string &name, const stdr_msgs::KinematicMsg params)
 Default constructor. More...
 
 ~OmniMotionController (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...
 

Detailed Description

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

Definition at line 53 of file omni_motion_controller.h.

Constructor & Destructor Documentation

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

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 48 of file omni_motion_controller.cpp.

stdr_robot::OmniMotionController::~OmniMotionController ( void  )

Default destructor.

Returns
void

Definition at line 97 of file omni_motion_controller.cpp.

Member Function Documentation

void stdr_robot::OmniMotionController::calculateMotion ( const ros::TimerEvent event)
virtual

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 68 of file omni_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 Mon Jun 10 2019 15:15:10