Abstract class that provides motion controller abstraction.
More...
#include <motion_controller_base.h>
Abstract class that provides motion controller abstraction.
Definition at line 44 of file motion_controller_base.h.
virtual stdr_robot::MotionController::~MotionController |
( |
void |
| ) |
|
|
inlinevirtual |
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 |
virtual void stdr_robot::MotionController::calculateMotion |
( |
const ros::TimerEvent & |
event | ) |
|
|
pure virtual |
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 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.
ros::Timer stdr_robot::MotionController::_calcTimer |
|
protected |
geometry_msgs::Twist stdr_robot::MotionController::_currentTwist |
|
protected |
stdr_msgs::KinematicMsg stdr_robot::MotionController::_motion_parameters |
|
protected |
const std::string& stdr_robot::MotionController::_namespace |
|
protected |
geometry_msgs::Pose2D stdr_robot::MotionController::_pose |
|
protected |
The documentation for this class was generated from the following file: