ROS-aware controller to manage a differential drive mobile base. This subcribes to cmd_vel topic, publishes odom and tf, and manages the two wheel joints.
More...
#include <diff_drive_base.h>
ROS-aware controller to manage a differential drive mobile base. This subcribes to cmd_vel topic, publishes odom and tf, and manages the two wheel joints.
Definition at line 63 of file diff_drive_base.h.
◆ DiffDriveBaseController()
robot_controllers::DiffDriveBaseController::DiffDriveBaseController |
( |
| ) |
|
◆ ~DiffDriveBaseController()
virtual robot_controllers::DiffDriveBaseController::~DiffDriveBaseController |
( |
| ) |
|
|
inlinevirtual |
◆ command()
void robot_controllers::DiffDriveBaseController::command |
( |
const geometry_msgs::TwistConstPtr & |
msg | ) |
|
Command callback from either a ROS topic, or a higher controller.
Definition at line 158 of file diff_drive_base.cpp.
◆ getClaimedNames()
std::vector< std::string > robot_controllers::DiffDriveBaseController::getClaimedNames |
( |
| ) |
|
|
virtual |
◆ getCommandedNames()
std::vector< std::string > robot_controllers::DiffDriveBaseController::getCommandedNames |
( |
| ) |
|
|
virtual |
◆ getType()
virtual std::string robot_controllers::DiffDriveBaseController::getType |
( |
| ) |
|
|
inlinevirtual |
◆ init()
Initialize the controller and any required data structures.
- Parameters
-
nh | Node handle for this controller. |
manager | The controller manager instance, this is needed for the controller to get information about joints, etc. |
- Returns
- 0 if succesfully configured, negative values are error codes.
Reimplemented from robot_controllers::Controller.
Definition at line 63 of file diff_drive_base.cpp.
◆ publishCallback()
void robot_controllers::DiffDriveBaseController::publishCallback |
( |
const ros::TimerEvent & |
event | ) |
|
|
private |
◆ reset()
bool robot_controllers::DiffDriveBaseController::reset |
( |
| ) |
|
|
virtual |
Cleanly reset the controller to it's initial state. Some controllers may choose to stop themselves. This is mainly used in the case of the the robot exiting some fault condition.
- Returns
- True if successfully reset, false otherwise.
Implements robot_controllers::Controller.
Definition at line 210 of file diff_drive_base.cpp.
◆ scanCallback()
void robot_controllers::DiffDriveBaseController::scanCallback |
( |
const sensor_msgs::LaserScanConstPtr & |
scan | ) |
|
|
private |
◆ setCommand()
void robot_controllers::DiffDriveBaseController::setCommand |
( |
float |
left, |
|
|
float |
right |
|
) |
| |
|
private |
◆ start()
bool robot_controllers::DiffDriveBaseController::start |
( |
| ) |
|
|
virtual |
◆ stop()
bool robot_controllers::DiffDriveBaseController::stop |
( |
bool |
force | ) |
|
|
virtual |
Attempt to stop the controller. This should be called only by the ControllerManager instance.
- Parameters
-
force | Should we force the controller to stop? Some controllers may wish to continue running until they absolutely have to stop. |
- Returns
- True if successfully stopped, false otherwise.
Implements robot_controllers::Controller.
Definition at line 193 of file diff_drive_base.cpp.
◆ update()
◆ broadcaster_
◆ cmd_sub_
◆ command_mutex_
boost::mutex robot_controllers::DiffDriveBaseController::command_mutex_ |
|
private |
◆ desired_r_
double robot_controllers::DiffDriveBaseController::desired_r_ |
|
private |
◆ desired_x_
double robot_controllers::DiffDriveBaseController::desired_x_ |
|
private |
◆ enabled_
bool robot_controllers::DiffDriveBaseController::enabled_ |
|
private |
◆ initialized_
bool robot_controllers::DiffDriveBaseController::initialized_ |
|
private |
◆ last_command_
ros::Time robot_controllers::DiffDriveBaseController::last_command_ |
|
private |
◆ last_laser_scan_
ros::Time robot_controllers::DiffDriveBaseController::last_laser_scan_ |
|
private |
◆ last_sent_r_
float robot_controllers::DiffDriveBaseController::last_sent_r_ |
|
private |
◆ last_sent_x_
float robot_controllers::DiffDriveBaseController::last_sent_x_ |
|
private |
◆ last_update_
ros::Time robot_controllers::DiffDriveBaseController::last_update_ |
|
private |
◆ left_
◆ left_last_position_
float robot_controllers::DiffDriveBaseController::left_last_position_ |
|
private |
◆ left_last_timestamp_
double robot_controllers::DiffDriveBaseController::left_last_timestamp_ |
|
private |
◆ manager_
◆ max_acceleration_r_
double robot_controllers::DiffDriveBaseController::max_acceleration_r_ |
|
private |
◆ max_acceleration_x_
double robot_controllers::DiffDriveBaseController::max_acceleration_x_ |
|
private |
◆ max_velocity_r_
double robot_controllers::DiffDriveBaseController::max_velocity_r_ |
|
private |
◆ max_velocity_x_
double robot_controllers::DiffDriveBaseController::max_velocity_x_ |
|
private |
◆ moving_threshold_
double robot_controllers::DiffDriveBaseController::moving_threshold_ |
|
private |
◆ odom_
nav_msgs::Odometry robot_controllers::DiffDriveBaseController::odom_ |
|
private |
◆ odom_mutex_
boost::mutex robot_controllers::DiffDriveBaseController::odom_mutex_ |
|
private |
◆ odom_pub_
◆ odom_timer_
ros::Timer robot_controllers::DiffDriveBaseController::odom_timer_ |
|
private |
◆ publish_tf_
bool robot_controllers::DiffDriveBaseController::publish_tf_ |
|
private |
◆ radians_per_meter_
double robot_controllers::DiffDriveBaseController::radians_per_meter_ |
|
private |
◆ ready_
bool robot_controllers::DiffDriveBaseController::ready_ |
|
private |
◆ right_
◆ right_last_position_
float robot_controllers::DiffDriveBaseController::right_last_position_ |
|
private |
◆ right_last_timestamp_
double robot_controllers::DiffDriveBaseController::right_last_timestamp_ |
|
private |
◆ robot_width_
double robot_controllers::DiffDriveBaseController::robot_width_ |
|
private |
◆ rotating_threshold_
double robot_controllers::DiffDriveBaseController::rotating_threshold_ |
|
private |
◆ safety_scaling_
double robot_controllers::DiffDriveBaseController::safety_scaling_ |
|
private |
◆ safety_scaling_distance_
double robot_controllers::DiffDriveBaseController::safety_scaling_distance_ |
|
private |
◆ scan_sub_
◆ theta_
double robot_controllers::DiffDriveBaseController::theta_ |
|
private |
◆ timeout_
ros::Duration robot_controllers::DiffDriveBaseController::timeout_ |
|
private |
◆ track_width_
double robot_controllers::DiffDriveBaseController::track_width_ |
|
private |
◆ wheel_rotating_threshold_
double robot_controllers::DiffDriveBaseController::wheel_rotating_threshold_ |
|
private |
The documentation for this class was generated from the following files: