44 RotateRecovery::RotateRecovery(): global_costmap_(NULL), local_costmap_(NULL),
45 tf_(NULL), initialized_(false), world_model_(NULL) {}
73 ROS_ERROR(
"You should not call initialize twice on this object, doing nothing");
83 ROS_ERROR(
"This object must be initialized before runBehavior is called");
88 ROS_ERROR(
"The costmaps passed to the RotateRecovery object cannot be NULL. Doing nothing.");
91 ROS_WARN(
"Rotate recovery behavior started.");
100 double current_angle = -1.0 * M_PI;
102 bool got_180 =
false;
112 double dist_left = M_PI - current_angle;
114 double x = global_pose.getOrigin().x(),
y = global_pose.getOrigin().y();
117 double sim_angle = 0.0;
118 while(sim_angle < dist_left){
119 double theta =
tf::getYaw(global_pose.getRotation()) + sim_angle;
123 if(footprint_cost < 0.0){
124 ROS_ERROR(
"Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f", footprint_cost);
137 geometry_msgs::Twist cmd_vel;
138 cmd_vel.linear.x = 0.0;
139 cmd_vel.linear.y = 0.0;
140 cmd_vel.angular.z = vel;
145 if(current_angle < 0.0)
149 if(got_180 && current_angle >= (0.0 -
tolerance_))
tf::TransformListener * tf_
void publish(const boost::shared_ptr< M > &message) const
base_local_planner::CostmapModel * world_model_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
~RotateRecovery()
Destructor for the rotate recovery behavior.
costmap_2d::Costmap2DROS * global_costmap_
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double max_rotational_vel_
costmap_2d::Costmap2DROS * local_costmap_
void runBehavior()
Run the RotateRecovery recovery behavior.
TFSIMD_FORCE_INLINE const tfScalar & y() const
double min_rotational_vel_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
TFSIMD_FORCE_INLINE const tfScalar & x() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
def normalize_angle(angle)
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)
std::vector< geometry_msgs::Point > getRobotFootprint()
A recovery behavior that rotates the robot in-place to attempt to clear out space.
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.