#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. More... | |
| MecanumDriveController () | |
| void | starting (const ros::Time &time) |
| Starts controller. More... | |
| void | stopping (const ros::Time &time) |
| Stops controller. More... | |
| void | update (const ros::Time &time, const ros::Duration &period) |
| Updates controller, i.e. computes the odometry and sets the new velocity commands. More... | |
Public Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface > | |
| Controller () | |
| virtual bool | init (hardware_interface::VelocityJointInterface *, ros::NodeHandle &) |
| virtual | ~Controller () |
Public Member Functions inherited from controller_interface::ControllerBase | |
| ControllerBase () | |
| bool | isRunning () |
| bool | isRunning () |
| bool | startRequest (const ros::Time &time) |
| bool | startRequest (const ros::Time &time) |
| bool | stopRequest (const ros::Time &time) |
| bool | stopRequest (const ros::Time &time) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| void | updateRequest (const ros::Time &time, const ros::Duration &period) |
| virtual | ~ControllerBase () |
Private Member Functions | |
| void | brake () |
| Brakes the wheels, i.e. sets the velocity to 0. More... | |
| void | cmdVelCallback (const geometry_msgs::Twist &command) |
| Velocity command callback. More... | |
| bool | getWheelRadius (const urdf::ModelInterfaceSharedPtr model, const urdf::LinkConstSharedPtr &wheel_link, double &wheel_radius) |
| Get the radius of a given wheel. More... | |
| void | setupRtPublishersMsg (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Sets the odometry publishing fields. More... | |
| 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. More... | |
Additional Inherited Members | |
Public Types inherited from controller_interface::ControllerBase | |
| typedef std::vector< hardware_interface::InterfaceResources > | ClaimedResources |
Public Attributes inherited from controller_interface::ControllerBase | |
| CONSTRUCTED | |
| INITIALIZED | |
| RUNNING | |
| enum controller_interface::ControllerBase:: { ... } | state_ |
Protected Member Functions inherited from controller_interface::Controller< hardware_interface::VelocityJointInterface > | |
| std::string | getHardwareInterfaceType () const |
| virtual bool | initRequest (hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh, ClaimedResources &claimed_resources) |
This class makes some assumptions on the model of the robot:
Definition at line 64 of file mecanum_drive_controller.h.
| mecanum_drive_controller::MecanumDriveController::MecanumDriveController | ( | ) |
Definition at line 81 of file mecanum_drive_controller.cpp.
|
private |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 296 of file mecanum_drive_controller.cpp.
|
private |
Velocity command callback.
| command | Velocity command message (twist) |
Definition at line 305 of file mecanum_drive_controller.cpp.
|
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 468 of file mecanum_drive_controller.cpp.
|
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 97 of file mecanum_drive_controller.cpp.
|
private |
Sets the odometry publishing fields.
| root_nh | Root node handle |
| controller_nh | Node handle inside the controller namespace |
Definition at line 508 of file mecanum_drive_controller.cpp.
|
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 328 of file mecanum_drive_controller.cpp.
|
virtual |
Starts controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 279 of file mecanum_drive_controller.cpp.
|
virtual |
Stops controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 290 of file mecanum_drive_controller.cpp.
|
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 190 of file mecanum_drive_controller.cpp.
|
private |
Frame to use for the robot base:
Definition at line 144 of file mecanum_drive_controller.h.
|
private |
Timeout to consider cmd_vel commands old:
Definition at line 141 of file mecanum_drive_controller.h.
|
private |
Definition at line 123 of file mecanum_drive_controller.h.
|
private |
Definition at line 124 of file mecanum_drive_controller.h.
|
private |
Whether to publish odometry to tf or not:
Definition at line 148 of file mecanum_drive_controller.h.
|
private |
Definition at line 154 of file mecanum_drive_controller.h.
|
private |
Definition at line 104 of file mecanum_drive_controller.h.
|
private |
Definition at line 157 of file mecanum_drive_controller.h.
|
private |
Definition at line 155 of file mecanum_drive_controller.h.
|
private |
Definition at line 156 of file mecanum_drive_controller.h.
|
private |
Definition at line 100 of file mecanum_drive_controller.h.
|
private |
Definition at line 131 of file mecanum_drive_controller.h.
|
private |
Definition at line 145 of file mecanum_drive_controller.h.
|
private |
Odometry related:
Definition at line 128 of file mecanum_drive_controller.h.
|
private |
Definition at line 130 of file mecanum_drive_controller.h.
|
private |
Definition at line 105 of file mecanum_drive_controller.h.
|
private |
Odometry related:
Definition at line 103 of file mecanum_drive_controller.h.
|
private |
Definition at line 125 of file mecanum_drive_controller.h.
|
private |
Definition at line 129 of file mecanum_drive_controller.h.
|
private |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 134 of file mecanum_drive_controller.h.
|
private |
Hardware handles:
Definition at line 108 of file mecanum_drive_controller.h.
|
private |
Definition at line 109 of file mecanum_drive_controller.h.
|
private |
Definition at line 110 of file mecanum_drive_controller.h.
|
private |
Definition at line 111 of file mecanum_drive_controller.h.
|
private |
Number of wheel joints:
Definition at line 151 of file mecanum_drive_controller.h.
|
private |
Definition at line 137 of file mecanum_drive_controller.h.
|
private |
Definition at line 138 of file mecanum_drive_controller.h.
|
private |
Definition at line 135 of file mecanum_drive_controller.h.
|
private |
Definition at line 136 of file mecanum_drive_controller.h.