42 #include <geometry_msgs/Twist.h> 43 #include <geometry_msgs/Point.h> 84 ROS_ERROR(
"You should not call initialize twice on this object, doing nothing");
97 ROS_ERROR(
"This object must be initialized before runBehavior is called");
103 ROS_ERROR(
"The costmap passed to the RotateRecovery object cannot be NULL. Doing nothing.");
106 ROS_WARN(
"Rotate recovery behavior started.");
112 geometry_msgs::PoseStamped global_pose;
115 double current_angle =
tf2::getYaw(global_pose.pose.orientation);
116 double start_angle = current_angle;
118 bool got_180 =
false;
126 current_angle =
tf2::getYaw(global_pose.pose.orientation);
134 dist_left = M_PI + distance_to_180;
147 double x = global_pose.pose.position.x, y = global_pose.pose.position.y;
150 double sim_angle = 0.0;
151 while (sim_angle < dist_left)
153 double theta = current_angle + sim_angle;
157 if (footprint_cost < 0.0)
159 ROS_ERROR(
"Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f",
173 geometry_msgs::Twist cmd_vel;
174 cmd_vel.linear.x = 0.0;
175 cmd_vel.linear.y = 0.0;
176 cmd_vel.angular.z = vel;
base_local_planner::CostmapModel * world_model_
~RotateRecovery()
Destructor for the rotate recovery behavior.
double max_rotational_vel_
RotateRecovery()
Constructor, make sure to call initialize in addition to actually initialize the object.
void runBehavior()
Run the RotateRecovery recovery behavior.
void initialize(std::string name, tf2_ros::Buffer *, costmap_2d::Costmap2DROS *, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void publish(const boost::shared_ptr< M > &message) const
double min_rotational_vel_
costmap_2d::Costmap2DROS * local_costmap_
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
double getYaw(const A &a)
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()
param_t loadParameterWithDeprecation(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name, const param_t &default_value)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
A recovery behavior that rotates the robot in-place to attempt to clear out space.
def shortest_angular_distance(from_angle, to_angle)