#include <ackermann_controller.h>
Classes | |
struct | Commands |
Velocity command related: More... | |
Public Member Functions | |
AckermannController () | |
std::string | getHardwareInterfaceType () const |
Get the name of this controller's hardware interface type. | |
bool | init (hardware_interface::PositionJointInterface *hw_pos, hardware_interface::VelocityJointInterface *hw_vel, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
virtual bool | initRequest (hardware_interface::RobotHW *const robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, std::set< std::string > &claimed_resources) |
Initialize controller. | |
void | starting (const ros::Time &time) |
Starts controller. | |
void | stopping (const ros::Time &time) |
Stops controller. | |
void | update (const ros::Time &time, const ros::Duration &period) |
Updates controller, i.e. computes the odometry and sets the new velocity commands. | |
Private Member Functions | |
void | brake () |
Brakes the wheels, i.e. sets the velocity to 0. | |
void | cmdAckermannCallback (const ackermann_msgs::AckermannDrive &command) |
Velocity command callback. | |
void | cmdVelCallback (const geometry_msgs::Twist &command) |
Velocity command callback. | |
bool | getWheelNames (ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names) |
Get the wheel names from a wheel param. | |
void | handleSteeringSaturation (double &front_left_steering, double &front_right_steering) |
Update the steering command with steering joint limitation to handle saturation
| |
void | setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
Sets the odometry publishing fields. | |
Private Attributes | |
std::string | base_frame_id_ |
Frame to use for the robot base: | |
double | cmd_vel_timeout_ |
Timeout to consider cmd_vel commands old: | |
realtime_tools::RealtimeBuffer < Commands > | command_ |
realtime_tools::RealtimeBuffer < Commands > | command_ackermann_ |
Ackermann command related: | |
Commands | command_struct_ |
Commands | command_struct_ackermann_ |
bool | enable_odom_tf_ |
Whether to publish odometry to tf or not: | |
bool | enable_twist_cmd_ |
Whether the control is make with ackermann msg or twist msg: | |
std::vector < hardware_interface::JointHandle > | front_steering_joints_ |
std::vector < hardware_interface::JointHandle > | front_wheel_joints_ |
Hardware handles: | |
double | front_wheel_radius_ |
Wheel radius (assuming it's the same for the left and right wheels): | |
Commands | last0_cmd_ |
Commands | last1_cmd_ |
Speed limiters: | |
ros::Time | last_state_publish_time_ |
SpeedLimiter | limiter_ang_ |
SpeedLimiter | limiter_lin_ |
std::string | name_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < nav_msgs::Odometry > > | odom_pub_ |
Odometry related: | |
Odometry | odometry_ |
bool | open_loop_ |
ros::Duration | publish_period_ |
Odometry related: | |
std::vector < hardware_interface::JointHandle > | rear_wheel_joints_ |
double | rear_wheel_radius_ |
double | steering_limit_ |
Joint steering limits (assuming the limit is the same for the left and right joint) | |
ros::Subscriber | sub_command_ |
ros::Subscriber | sub_command_ackermann_ |
boost::shared_ptr < realtime_tools::RealtimePublisher < tf::tfMessage > > | tf_odom_pub_ |
double | track_ |
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel width): | |
double | wheel_base_ |
Wheel base (distance between front and rear wheel): |
This class makes some assumptions on the model of the robot:
Definition at line 28 of file ackermann_controller.h.
Definition at line 15 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::brake | ( | ) | [private] |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 440 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::cmdAckermannCallback | ( | const ackermann_msgs::AckermannDrive & | command | ) | [private] |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 476 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::cmdVelCallback | ( | const geometry_msgs::Twist & | command | ) | [private] |
Velocity command callback.
command | Velocity command message (twist) |
Definition at line 456 of file ackermann_controller.cpp.
std::string ackermann_controller::AckermannController::getHardwareInterfaceType | ( | ) | const [inline, virtual] |
Get the name of this controller's hardware interface type.
Implements controller_interface::ControllerBase.
Definition at line 46 of file ackermann_controller.h.
bool ackermann_controller::AckermannController::getWheelNames | ( | ros::NodeHandle & | controller_nh, |
const std::string & | wheel_param, | ||
std::vector< std::string > & | wheel_names | ||
) | [private] |
Get the wheel names from a wheel param.
[in] | controller_nh | Controller node handler |
[in] | wheel_param | Param name |
[out] | wheel_names | Vector with the whel names |
Definition at line 496 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::handleSteeringSaturation | ( | double & | front_left_steering, |
double & | front_right_steering | ||
) | [private] |
Update the steering command with steering joint limitation to handle saturation
.
front_left_steering | |
front_right_steering |
Definition at line 596 of file ackermann_controller.cpp.
bool ackermann_controller::AckermannController::init | ( | hardware_interface::PositionJointInterface * | hw_pos, |
hardware_interface::VelocityJointInterface * | hw_vel, | ||
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh | ||
) |
Definition at line 81 of file ackermann_controller.cpp.
bool ackermann_controller::AckermannController::initRequest | ( | hardware_interface::RobotHW *const | robot_hw, |
ros::NodeHandle & | root_nh, | ||
ros::NodeHandle & | controller_nh, | ||
std::set< std::string > & | claimed_resources | ||
) | [virtual] |
Initialize controller.
robot_hw | Velocity joint interface for the wheels |
root_nh | Node handle at root namespace |
controller_nh | Node handle inside the controller namespace |
claimed_resources | Vector of JointInterfaces claimed during init |
Implements controller_interface::ControllerBase.
Definition at line 31 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::setOdomPubFields | ( | ros::NodeHandle & | root_nh, |
ros::NodeHandle & | controller_nh | ||
) | [private] |
Sets the odometry publishing fields.
root_nh | Root node handle |
controller_nh | Node handle inside the controller namespace |
Definition at line 549 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::starting | ( | const ros::Time & | time | ) | [virtual] |
Starts controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 425 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::stopping | ( | const ros::Time & | time | ) | [virtual] |
Stops controller.
time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 435 of file ackermann_controller.cpp.
void ackermann_controller::AckermannController::update | ( | const ros::Time & | time, |
const ros::Duration & | period | ||
) | [virtual] |
Updates controller, i.e. computes the odometry and sets the new velocity commands.
time | Current time |
period | Time since the last called to update |
check limits to not apply the same steering on right and left when saturated !
Implements controller_interface::ControllerBase.
Definition at line 262 of file ackermann_controller.cpp.
std::string ackermann_controller::AckermannController::base_frame_id_ [private] |
Frame to use for the robot base:
Definition at line 129 of file ackermann_controller.h.
double ackermann_controller::AckermannController::cmd_vel_timeout_ [private] |
Timeout to consider cmd_vel commands old:
Definition at line 126 of file ackermann_controller.h.
realtime_tools::RealtimeBuffer<Commands> ackermann_controller::AckermannController::command_ [private] |
Definition at line 98 of file ackermann_controller.h.
realtime_tools::RealtimeBuffer<Commands> ackermann_controller::AckermannController::command_ackermann_ [private] |
Ackermann command related:
Definition at line 103 of file ackermann_controller.h.
Definition at line 99 of file ackermann_controller.h.
Definition at line 104 of file ackermann_controller.h.
bool ackermann_controller::AckermannController::enable_odom_tf_ [private] |
Whether to publish odometry to tf or not:
Definition at line 132 of file ackermann_controller.h.
bool ackermann_controller::AckermannController::enable_twist_cmd_ [private] |
Whether the control is make with ackermann msg or twist msg:
Definition at line 135 of file ackermann_controller.h.
std::vector<hardware_interface::JointHandle> ackermann_controller::AckermannController::front_steering_joints_ [private] |
Definition at line 86 of file ackermann_controller.h.
std::vector<hardware_interface::JointHandle> ackermann_controller::AckermannController::front_wheel_joints_ [private] |
Hardware handles:
Definition at line 84 of file ackermann_controller.h.
double ackermann_controller::AckermannController::front_wheel_radius_ [private] |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 117 of file ackermann_controller.h.
Definition at line 139 of file ackermann_controller.h.
Speed limiters:
Definition at line 138 of file ackermann_controller.h.
Definition at line 80 of file ackermann_controller.h.
Definition at line 141 of file ackermann_controller.h.
Definition at line 140 of file ackermann_controller.h.
std::string ackermann_controller::AckermannController::name_ [private] |
Definition at line 76 of file ackermann_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > ackermann_controller::AckermannController::odom_pub_ [private] |
Odometry related:
Definition at line 108 of file ackermann_controller.h.
Definition at line 110 of file ackermann_controller.h.
bool ackermann_controller::AckermannController::open_loop_ [private] |
Definition at line 81 of file ackermann_controller.h.
Odometry related:
Definition at line 79 of file ackermann_controller.h.
std::vector<hardware_interface::JointHandle> ackermann_controller::AckermannController::rear_wheel_joints_ [private] |
Definition at line 85 of file ackermann_controller.h.
double ackermann_controller::AckermannController::rear_wheel_radius_ [private] |
Definition at line 117 of file ackermann_controller.h.
double ackermann_controller::AckermannController::steering_limit_ [private] |
Joint steering limits (assuming the limit is the same for the left and right joint)
Definition at line 120 of file ackermann_controller.h.
Definition at line 100 of file ackermann_controller.h.
Definition at line 105 of file ackermann_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > ackermann_controller::AckermannController::tf_odom_pub_ [private] |
Definition at line 109 of file ackermann_controller.h.
double ackermann_controller::AckermannController::track_ [private] |
Wheel separation (or track), distance between left and right wheels (from the midpoint of the wheel width):
Definition at line 114 of file ackermann_controller.h.
double ackermann_controller::AckermannController::wheel_base_ [private] |
Wheel base (distance between front and rear wheel):
Definition at line 123 of file ackermann_controller.h.