A move base plugin that implements car like maneuvers as a recovery behavior. More...
#include <car_maneuver_recovery.h>

Public Member Functions | |
| CarManeuverRecovery () | |
| Constructor. More... | |
| void | initialize (std::string name, tf::TransformListener *tfListener, costmap_2d::Costmap2DROS *globalCostmapROS, costmap_2d::Costmap2DROS *localCostmapROS) |
| Initializes plugin. More... | |
| double | lineCost (geometry_msgs::Point point1, geometry_msgs::Point point2) |
| Calculates line cost. More... | |
| void | runBehavior () |
| Executes the car maneuver recovery behavior. More... | |
| ~CarManeuverRecovery () | |
| Destructor. More... | |
Private Attributes | |
| bool | crabSteering_ |
| use crab steering instead of counter steering or ackermann steering More... | |
| bool | fourWheelSteering_ |
| four wheel steering status More... | |
| costmap_2d::Costmap2DROS * | globalCostmapROS_ |
| global costmap ros wrapper ptr More... | |
| bool | initialized_ |
| contains the initialization state of the plugin More... | |
| costmap_2d::Costmap2DROS * | localCostmapROS_ |
| local costmap ros wrapper ptr More... | |
| std::string | name_ |
| name of instance More... | |
| double | recoverySpeed_ |
| max speed of robot More... | |
| double | recoverySteeringAngle_ |
| max steering angle of robot More... | |
| tf::TransformListener * | tfListener_ |
| tf transform listener More... | |
| double | timeout_ |
| recovery behavior timeout More... | |
| ros::Publisher | twistPub_ |
| twist publisher More... | |
| double | wheelbase_ |
| wheelbase of robot More... | |
| base_local_planner::CostmapModel * | worldModel_ |
| costmap world model More... | |
A move base plugin that implements car like maneuvers as a recovery behavior.
Definition at line 56 of file car_maneuver_recovery.h.
| car_maneuver_recovery::CarManeuverRecovery::CarManeuverRecovery | ( | ) |
Constructor.
| car_maneuver_recovery::CarManeuverRecovery::~CarManeuverRecovery | ( | ) |
Destructor.
| void car_maneuver_recovery::CarManeuverRecovery::initialize | ( | std::string | name, |
| tf::TransformListener * | tfListener, | ||
| costmap_2d::Costmap2DROS * | globalCostmapROS, | ||
| costmap_2d::Costmap2DROS * | localCostmapROS | ||
| ) |
Initializes plugin.
| name | name of instance |
| tfListener | ptr to the tf transform listener of the node |
| globalCostmapROS | ptr to the global costmap of the node |
| localCostmapROS | ptr to the local costmap of the node |
| double car_maneuver_recovery::CarManeuverRecovery::lineCost | ( | geometry_msgs::Point | point1, |
| geometry_msgs::Point | point2 | ||
| ) |
Calculates line cost.
| point1 | line start point |
| point2 | line end point |
| void car_maneuver_recovery::CarManeuverRecovery::runBehavior | ( | ) |
Executes the car maneuver recovery behavior.
|
private |
use crab steering instead of counter steering or ackermann steering
Definition at line 121 of file car_maneuver_recovery.h.
|
private |
four wheel steering status
Definition at line 119 of file car_maneuver_recovery.h.
|
private |
global costmap ros wrapper ptr
Definition at line 108 of file car_maneuver_recovery.h.
|
private |
contains the initialization state of the plugin
Definition at line 98 of file car_maneuver_recovery.h.
|
private |
local costmap ros wrapper ptr
Definition at line 106 of file car_maneuver_recovery.h.
|
private |
name of instance
Definition at line 96 of file car_maneuver_recovery.h.
|
private |
max speed of robot
Definition at line 113 of file car_maneuver_recovery.h.
|
private |
max steering angle of robot
Definition at line 115 of file car_maneuver_recovery.h.
|
private |
tf transform listener
Definition at line 104 of file car_maneuver_recovery.h.
|
private |
recovery behavior timeout
Definition at line 123 of file car_maneuver_recovery.h.
|
private |
twist publisher
Definition at line 101 of file car_maneuver_recovery.h.
|
private |
wheelbase of robot
Definition at line 117 of file car_maneuver_recovery.h.
|
private |
costmap world model
Definition at line 110 of file car_maneuver_recovery.h.