#include <mecanum_drive_controller.h>

Classes | |
| struct | Commands |
| Velocity command related: More... | |
Public Member Functions | |
| bool | init (hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Initialize controller. | |
| MecanumDriveController () | |
| 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 | cmdVelCallback (const geometry_msgs::Twist &command) |
| Velocity command callback. | |
| bool | getWheelRadius (const boost::shared_ptr< urdf::ModelInterface > model, const boost::shared_ptr< const urdf::Link > &wheel_link, double &wheel_radius) |
| Get the radius of a given wheel. | |
| void | setupRtPublishersMsg (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Sets the odometry publishing fields. | |
| bool | setWheelParamsFromUrdf (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, const std::string &wheel0_name, const std::string &wheel1_name, const std::string &wheel2_name, const std::string &wheel3_name) |
| Sets odometry parameters from the URDF, i.e. the wheel radius and separation. | |
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_ |
| Commands | command_struct_ |
| bool | enable_odom_tf_ |
| Whether to publish odometry to tf or not: | |
| Commands | last_cmd_ |
| ros::Time | last_state_publish_time_ |
| SpeedLimiter | limiter_ang_ |
| SpeedLimiter | limiter_linX_ |
| SpeedLimiter | limiter_linY_ |
| std::string | name_ |
| geometry_msgs::TransformStamped | odom_frame_ |
| boost::shared_ptr < realtime_tools::RealtimePublisher < nav_msgs::Odometry > > | odom_pub_ |
| Odometry related: | |
| Odometry | odometry_ |
| bool | open_loop_ |
| ros::Duration | publish_period_ |
| Odometry related: | |
| ros::Subscriber | sub_command_ |
| boost::shared_ptr < realtime_tools::RealtimePublisher < tf::tfMessage > > | tf_odom_pub_ |
| bool | use_realigned_roller_joints_ |
| Wheel radius (assuming it's the same for the left and right wheels): | |
| hardware_interface::JointHandle | wheel0_jointHandle_ |
| Hardware handles: | |
| hardware_interface::JointHandle | wheel1_jointHandle_ |
| hardware_interface::JointHandle | wheel2_jointHandle_ |
| hardware_interface::JointHandle | wheel3_jointHandle_ |
| size_t | wheel_joints_size_ |
| Number of wheel joints: | |
| double | wheel_separation_x_ |
| double | wheel_separation_y_ |
| double | wheels_k_ |
| double | wheels_radius_ |
This class makes some assumptions on the model of the robot:
Definition at line 64 of file mecanum_drive_controller.h.
Definition at line 81 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::brake | ( | ) | [private] |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 292 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::cmdVelCallback | ( | const geometry_msgs::Twist & | command | ) | [private] |
Velocity command callback.
| command | Velocity command message (twist) |
Definition at line 301 of file mecanum_drive_controller.cpp.
| bool mecanum_drive_controller::MecanumDriveController::getWheelRadius | ( | const boost::shared_ptr< urdf::ModelInterface > | model, |
| const boost::shared_ptr< const urdf::Link > & | wheel_link, | ||
| double & | wheel_radius | ||
| ) | [private] |
Get the radius of a given wheel.
| model | urdf model used | |
| wheel_link | link of the wheel from which to get the radius | |
| [out] | wheels_radius | radius of the wheel read from the urdf |
Definition at line 464 of file mecanum_drive_controller.cpp.
| bool mecanum_drive_controller::MecanumDriveController::init | ( | hardware_interface::VelocityJointInterface * | hw, |
| ros::NodeHandle & | root_nh, | ||
| ros::NodeHandle & | controller_nh | ||
| ) | [virtual] |
Initialize controller.
| hw | Velocity joint interface for the wheels |
| root_nh | Node handle at root namespace |
| controller_nh | Node handle inside the controller namespace |
Reimplemented from controller_interface::Controller< hardware_interface::VelocityJointInterface >.
Definition at line 96 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::setupRtPublishersMsg | ( | 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 504 of file mecanum_drive_controller.cpp.
| bool mecanum_drive_controller::MecanumDriveController::setWheelParamsFromUrdf | ( | ros::NodeHandle & | root_nh, |
| ros::NodeHandle & | controller_nh, | ||
| const std::string & | wheel0_name, | ||
| const std::string & | wheel1_name, | ||
| const std::string & | wheel2_name, | ||
| const std::string & | wheel3_name | ||
| ) | [private] |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
| root_nh | Root node handle |
| wheel0_name | Name of wheel0 joint |
| wheel1_name | Name of wheel1 joint |
| wheel2_name | Name of wheel2 joint |
| wheel3_name | Name of wheel3 joint |
Definition at line 324 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::starting | ( | const ros::Time & | time | ) | [virtual] |
Starts controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 275 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::stopping | ( | const ros::Time & | time | ) | [virtual] |
Stops controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 286 of file mecanum_drive_controller.cpp.
| void mecanum_drive_controller::MecanumDriveController::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 |
Implements controller_interface::ControllerBase.
Definition at line 186 of file mecanum_drive_controller.cpp.
std::string mecanum_drive_controller::MecanumDriveController::base_frame_id_ [private] |
Frame to use for the robot base:
Definition at line 144 of file mecanum_drive_controller.h.
double mecanum_drive_controller::MecanumDriveController::cmd_vel_timeout_ [private] |
Timeout to consider cmd_vel commands old:
Definition at line 141 of file mecanum_drive_controller.h.
realtime_tools::RealtimeBuffer<Commands> mecanum_drive_controller::MecanumDriveController::command_ [private] |
Definition at line 123 of file mecanum_drive_controller.h.
Definition at line 124 of file mecanum_drive_controller.h.
Whether to publish odometry to tf or not:
Definition at line 147 of file mecanum_drive_controller.h.
Definition at line 153 of file mecanum_drive_controller.h.
Definition at line 104 of file mecanum_drive_controller.h.
Definition at line 156 of file mecanum_drive_controller.h.
Definition at line 154 of file mecanum_drive_controller.h.
Definition at line 155 of file mecanum_drive_controller.h.
std::string mecanum_drive_controller::MecanumDriveController::name_ [private] |
Definition at line 100 of file mecanum_drive_controller.h.
geometry_msgs::TransformStamped mecanum_drive_controller::MecanumDriveController::odom_frame_ [private] |
Definition at line 131 of file mecanum_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<nav_msgs::Odometry> > mecanum_drive_controller::MecanumDriveController::odom_pub_ [private] |
Odometry related:
Definition at line 128 of file mecanum_drive_controller.h.
Definition at line 130 of file mecanum_drive_controller.h.
bool mecanum_drive_controller::MecanumDriveController::open_loop_ [private] |
Definition at line 105 of file mecanum_drive_controller.h.
Odometry related:
Definition at line 103 of file mecanum_drive_controller.h.
Definition at line 125 of file mecanum_drive_controller.h.
boost::shared_ptr<realtime_tools::RealtimePublisher<tf::tfMessage> > mecanum_drive_controller::MecanumDriveController::tf_odom_pub_ [private] |
Definition at line 129 of file mecanum_drive_controller.h.
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 134 of file mecanum_drive_controller.h.
hardware_interface::JointHandle mecanum_drive_controller::MecanumDriveController::wheel0_jointHandle_ [private] |
Hardware handles:
Definition at line 108 of file mecanum_drive_controller.h.
hardware_interface::JointHandle mecanum_drive_controller::MecanumDriveController::wheel1_jointHandle_ [private] |
Definition at line 109 of file mecanum_drive_controller.h.
hardware_interface::JointHandle mecanum_drive_controller::MecanumDriveController::wheel2_jointHandle_ [private] |
Definition at line 110 of file mecanum_drive_controller.h.
hardware_interface::JointHandle mecanum_drive_controller::MecanumDriveController::wheel3_jointHandle_ [private] |
Definition at line 111 of file mecanum_drive_controller.h.
size_t mecanum_drive_controller::MecanumDriveController::wheel_joints_size_ [private] |
Number of wheel joints:
Definition at line 150 of file mecanum_drive_controller.h.
Definition at line 137 of file mecanum_drive_controller.h.
Definition at line 138 of file mecanum_drive_controller.h.
double mecanum_drive_controller::MecanumDriveController::wheels_k_ [private] |
Definition at line 135 of file mecanum_drive_controller.h.
double mecanum_drive_controller::MecanumDriveController::wheels_radius_ [private] |
Definition at line 136 of file mecanum_drive_controller.h.