#include <diff_drive_controller.h>

Classes | |
| struct | Commands |
| Velocity command related: More... | |
| struct | DynamicParams |
Public Member Functions | |
| DiffDriveController () | |
| bool | init (hardware_interface::VelocityJointInterface *hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Initialize controller. More... | |
| void | starting (const ros::Time &time) |
| Starts controller. More... | |
| void | stopping (const ros::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 Types | |
| typedef dynamic_reconfigure::Server< DiffDriveControllerConfig > | ReconfigureServer |
| Dynamic Reconfigure server. More... | |
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 | getWheelNames (ros::NodeHandle &controller_nh, const std::string &wheel_param, std::vector< std::string > &wheel_names) |
| Get the wheel names from a wheel param. More... | |
| void | reconfCallback (DiffDriveControllerConfig &config, uint32_t) |
| Callback for dynamic_reconfigure server. More... | |
| bool | setOdomParamsFromUrdf (ros::NodeHandle &root_nh, const std::string &left_wheel_name, const std::string &right_wheel_name, bool lookup_wheel_separation, bool lookup_wheel_radius) |
| Sets odometry parameters from the URDF, i.e. the wheel radius and separation. More... | |
| void | setOdomPubFields (ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) |
| Sets the odometry publishing fields. More... | |
| void | updateDynamicParams () |
| Update the dynamic parameters in the RT loop. 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 66 of file diff_drive_controller.h.
|
private |
Dynamic Reconfigure server.
Definition at line 217 of file diff_drive_controller.h.
| diff_drive_controller::DiffDriveController::DiffDriveController | ( | ) |
Definition at line 152 of file diff_drive_controller.cpp.
|
private |
Brakes the wheels, i.e. sets the velocity to 0.
Definition at line 479 of file diff_drive_controller.cpp.
|
private |
Velocity command callback.
| command | Velocity command message (twist) |
Definition at line 489 of file diff_drive_controller.cpp.
|
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 518 of file diff_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 170 of file diff_drive_controller.cpp.
|
private |
Callback for dynamic_reconfigure server.
| config | The config set from dynamic_reconfigure server |
| level | not used at this time. |
Definition at line 687 of file diff_drive_controller.cpp.
|
private |
Sets odometry parameters from the URDF, i.e. the wheel radius and separation.
| root_nh | Root node handle |
| left_wheel_name | Name of the left wheel joint |
| right_wheel_name | Name of the right wheel joint |
Definition at line 571 of file diff_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 640 of file diff_drive_controller.cpp.
|
virtual |
Starts controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 464 of file diff_drive_controller.cpp.
|
virtual |
Stops controller.
| time | Current time |
Reimplemented from controller_interface::ControllerBase.
Definition at line 474 of file diff_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 352 of file diff_drive_controller.cpp.
|
private |
Update the dynamic parameters in the RT loop.
Definition at line 703 of file diff_drive_controller.cpp.
|
private |
Whether to allow multiple publishers on cmd_vel topic or not:
Definition at line 149 of file diff_drive_controller.h.
|
private |
Frame to use for the robot base:
Definition at line 152 of file diff_drive_controller.h.
|
private |
Publish executed commands.
Definition at line 127 of file diff_drive_controller.h.
|
private |
Timeout to consider cmd_vel commands old:
Definition at line 146 of file diff_drive_controller.h.
|
private |
Definition at line 122 of file diff_drive_controller.h.
|
private |
Definition at line 123 of file diff_drive_controller.h.
|
private |
Definition at line 218 of file diff_drive_controller.h.
|
private |
Definition at line 214 of file diff_drive_controller.h.
|
private |
Whether to publish odometry to tf or not:
Definition at line 158 of file diff_drive_controller.h.
|
private |
Definition at line 165 of file diff_drive_controller.h.
|
private |
Speed limiters:
Definition at line 164 of file diff_drive_controller.h.
|
private |
Definition at line 106 of file diff_drive_controller.h.
|
private |
Hardware handles:
Definition at line 110 of file diff_drive_controller.h.
|
private |
Definition at line 142 of file diff_drive_controller.h.
|
private |
Definition at line 167 of file diff_drive_controller.h.
|
private |
Definition at line 166 of file diff_drive_controller.h.
|
private |
Definition at line 102 of file diff_drive_controller.h.
|
private |
Frame to use for odometry and odom tf:
Definition at line 155 of file diff_drive_controller.h.
|
private |
Odometry related:
Definition at line 130 of file diff_drive_controller.h.
|
private |
Definition at line 132 of file diff_drive_controller.h.
|
private |
Definition at line 107 of file diff_drive_controller.h.
|
private |
Publish limited velocity:
Definition at line 170 of file diff_drive_controller.h.
|
private |
Odometry related:
Definition at line 105 of file diff_drive_controller.h.
|
private |
Definition at line 111 of file diff_drive_controller.h.
|
private |
Definition at line 143 of file diff_drive_controller.h.
|
private |
Definition at line 124 of file diff_drive_controller.h.
|
private |
Definition at line 131 of file diff_drive_controller.h.
|
private |
Number of wheel joints:
Definition at line 161 of file diff_drive_controller.h.
|
private |
Wheel radius (assuming it's the same for the left and right wheels):
Definition at line 138 of file diff_drive_controller.h.
|
private |
Wheel separation, wrt the midpoint of the wheel width:
Definition at line 135 of file diff_drive_controller.h.
|
private |
Wheel separation and radius calibration multipliers:
Definition at line 141 of file diff_drive_controller.h.