40 #include <geometry_msgs/Twist.h> 41 #include <geometry_msgs/Point.h> 52 RotateRecovery::RotateRecovery(): local_costmap_(NULL), initialized_(false), world_model_(NULL)
82 ROS_ERROR(
"You should not call initialize twice on this object, doing nothing");
95 ROS_ERROR(
"This object must be initialized before runBehavior is called");
101 ROS_ERROR(
"The costmap passed to the RotateRecovery object cannot be NULL. Doing nothing.");
104 ROS_WARN(
"Rotate recovery behavior started.");
113 double current_angle =
tf::getYaw(global_pose.getRotation());
114 double start_angle = current_angle;
116 bool got_180 =
false;
124 current_angle =
tf::getYaw(global_pose.getRotation());
132 dist_left = M_PI + distance_to_180;
145 double x = global_pose.getOrigin().x(),
y = global_pose.getOrigin().y();
148 double sim_angle = 0.0;
149 while (sim_angle < dist_left)
151 double theta = current_angle + sim_angle;
155 if (footprint_cost < 0.0)
157 ROS_ERROR(
"Rotate recovery can't rotate in place because there is a potential collision. Cost: %.2f",
171 geometry_msgs::Twist cmd_vel;
172 cmd_vel.linear.x = 0.0;
173 cmd_vel.linear.y = 0.0;
174 cmd_vel.angular.z = vel;
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.
static double getYaw(const Quaternion &bt_q)
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double max_rotational_vel_
void runBehavior()
Run the RotateRecovery recovery behavior.
TFSIMD_FORCE_INLINE const tfScalar & y() const
double min_rotational_vel_
costmap_2d::Costmap2DROS * local_costmap_
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)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
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.
def shortest_angular_distance(from_angle, to_angle)
void initialize(std::string name, tf::TransformListener *, costmap_2d::Costmap2DROS *, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.