38 #ifndef CAR_MANEUVER_RECOVERY_CAR_MANEUVER_RECOVERY_H
39 #define CAR_MANEUVER_RECOVERY_CAR_MANEUVER_RECOVERY_H
43 #include <costmap_2d/costmap_2d_ros.h>
44 #include <nav_core/recovery_behavior.h>
45 #include <base_local_planner/costmap_model.h>
46 #include <geometry_msgs/Twist.h>
48 namespace car_maneuver_recovery
77 void initialize(std::string name, tf::TransformListener* tfListener,
78 costmap_2d::Costmap2DROS* globalCostmapROS,
79 costmap_2d::Costmap2DROS* localCostmapROS);
91 double lineCost(geometry_msgs::Point point1, geometry_msgs::Point point2);
130 #endif // CAR_MANEUVER_RECOVERY_CAR_MANEUVER_RECOVERY_H
base_local_planner::CostmapModel * worldModel_
costmap world model
ros::Publisher twistPub_
twist publisher
void initialize(std::string name, tf::TransformListener *tfListener, costmap_2d::Costmap2DROS *globalCostmapROS, costmap_2d::Costmap2DROS *localCostmapROS)
Initializes plugin.
double recoverySteeringAngle_
max steering angle of robot
costmap_2d::Costmap2DROS * globalCostmapROS_
global costmap ros wrapper ptr
A move base plugin that implements car like maneuvers as a recovery behavior.
double timeout_
recovery behavior timeout
double wheelbase_
wheelbase of robot
double lineCost(geometry_msgs::Point point1, geometry_msgs::Point point2)
Calculates line cost.
costmap_2d::Costmap2DROS * localCostmapROS_
local costmap ros wrapper ptr
std::string name_
name of instance
CarManeuverRecovery()
Constructor.
void runBehavior()
Executes the car maneuver recovery behavior.
~CarManeuverRecovery()
Destructor.
bool initialized_
contains the initialization state of the plugin
bool fourWheelSteering_
four wheel steering status
double recoverySpeed_
max speed of robot
tf::TransformListener * tfListener_
tf transform listener
bool crabSteering_
use crab steering instead of counter steering or ackermann steering