45 SBPLRecovery::SBPLRecovery():
46 global_costmap_(NULL),
60 std::string plan_topic;
61 p_nh.
param(
"plan_topic", plan_topic, std::string(
"NavfnROS/plan"));
68 double planning_distance;
69 p_nh.
param(
"planning_distance", planning_distance, 2.0);
105 std::vector<geometry_msgs::PoseStamped> transformed_plan;
109 if(!transformed_plan.empty())
110 plan_.header = transformed_plan[0].header;
111 plan_.poses = transformed_plan;
114 ROS_WARN(
"Could not transform to frame of the local recovery");
124 const geometry_msgs::PoseStamped& p2)
126 return (p1.pose.position.x - p2.pose.position.x) * (p1.pose.position.x - p2.pose.position.x) +
127 (p1.pose.position.y - p2.pose.position.y) * (p1.pose.position.y - p2.pose.position.y);
133 std::vector<geometry_msgs::PoseStamped> sbpl_plan;
140 ROS_ERROR(
"SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
148 ROS_ERROR(
"SBPL recovery behavior could not get the current pose of the robot. Doing nothing.");
153 geometry_msgs::PoseStamped start;
159 unsigned int index = 0;
160 for(index=0; index <
plan_.poses.size(); ++index)
168 int unsuccessful_attempts = 0;
169 for(
unsigned int i = index; i <
plan_.poses.size(); ++i)
171 ROS_DEBUG(
"SQ Distance: %.2f, spd: %.2f, start (%.2f, %.2f), goal (%.2f, %.2f)",
174 start.pose.position.x, start.pose.position.y,
175 plan_.poses[i].pose.position.x,
176 plan_.poses[i].pose.position.y);
179 ROS_INFO(
"Calling sbpl planner with start (%.2f, %.2f), goal (%.2f, %.2f)",
180 start.pose.position.x, start.pose.position.y,
181 plan_.poses[i].pose.position.x,
182 plan_.poses[i].pose.position.y);
191 unsuccessful_attempts++;
204 ROS_ERROR(
"Please initialize this recovery behavior before attempting to run it.");
208 ROS_INFO(
"Starting the sbpl recovery behavior");
212 std::vector<geometry_msgs::PoseStamped> sbpl_plan =
makePlan();
214 if(sbpl_plan.empty())
216 ROS_ERROR(
"Unable to find a valid pose to plan to on the global plan.");
228 geometry_msgs::Twist cmd_vel;
239 ROS_INFO(
"The sbpl recovery behavior made it to its desired goal");
241 ROS_WARN(
"The sbpl recovery behavior failed to make it to its desired goal");
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
void publish(const boost::shared_ptr< M > &message) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
ros::Subscriber plan_sub_
costmap_2d::Costmap2DROS * local_costmap_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
tf::TransformListener * tf_
costmap_2d::Costmap2DROS * global_costmap_
bool transformGlobalPlan(const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const tf::Stamped< tf::Pose > &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
pose_follower::PoseFollower local_planner_
double control_frequency_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros)
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
double controller_patience_
std::vector< geometry_msgs::PoseStamped > makePlan()
double sqDistance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
double sq_planning_distance_
void planCB(const nav_msgs::Path::ConstPtr &plan)