sbpl_recovery.h
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of Willow Garage, Inc. nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *
35 * Author: Eitan Marder-Eppstein
36 *********************************************************************/
37 #ifndef SBPL_RECOVERY_SBPL_RECOVERY_H_
38 #define SBPL_RECOVERY_SBPL_RECOVERY_H_
39 
40 #include <ros/ros.h>
45 #include <geometry_msgs/PoseStamped.h>
46 #include <nav_msgs/Path.h>
47 #include <boost/thread.hpp>
49 #include <tf2_ros/buffer.h>
50 
51 namespace sbpl_recovery
52 {
54  {
55  public:
56  SBPLRecovery();
57 
58  // Initialize the parameters of the behavior
59  void initialize (std::string n, tf2_ros::Buffer* tf,
60  costmap_2d::Costmap2DROS* global_costmap,
61  costmap_2d::Costmap2DROS* local_costmap);
62 
63  // Run the behavior
64  void runBehavior();
65 
66  private:
67  void planCB(const nav_msgs::Path::ConstPtr& plan);
68  double sqDistance(const geometry_msgs::PoseStamped& p1,
69  const geometry_msgs::PoseStamped& p2);
70  std::vector<geometry_msgs::PoseStamped> makePlan();
71 
77  bool initialized_;
80  boost::mutex plan_mutex_;
81  nav_msgs::Path plan_;
84  bool use_local_frame_;
85  };
86 
87 };
88 #endif
sbpl_recovery::SBPLRecovery::attempts_per_run_
int attempts_per_run_
Definition: sbpl_recovery.h:153
pose_follower.h
sbpl_recovery::SBPLRecovery::plan_mutex_
boost::mutex plan_mutex_
Definition: sbpl_recovery.h:150
ros::Publisher
sbpl_recovery::SBPLRecovery::makePlan
std::vector< geometry_msgs::PoseStamped > makePlan()
Definition: sbpl_recovery.cpp:165
sbpl_recovery::SBPLRecovery::sq_planning_distance_
double sq_planning_distance_
Definition: sbpl_recovery.h:152
sbpl_recovery::SBPLRecovery::SBPLRecovery
SBPLRecovery()
Definition: sbpl_recovery.cpp:80
sbpl_recovery::SBPLRecovery::planCB
void planCB(const nav_msgs::Path::ConstPtr &plan)
Definition: sbpl_recovery.cpp:128
ros.h
goal_functions.h
sbpl_recovery::SBPLRecovery::global_costmap_
costmap_2d::Costmap2DROS * global_costmap_
Definition: sbpl_recovery.h:142
buffer.h
sbpl_lattice_planner::SBPLLatticePlanner
sbpl_recovery
Definition: sbpl_recovery.h:51
costmap_2d_ros.h
sbpl_recovery::SBPLRecovery::control_frequency_
double control_frequency_
Definition: sbpl_recovery.h:152
sbpl_recovery::SBPLRecovery::plan_sub_
ros::Subscriber plan_sub_
Definition: sbpl_recovery.h:148
sbpl_recovery::SBPLRecovery::vel_pub_
ros::Publisher vel_pub_
Definition: sbpl_recovery.h:149
sbpl_recovery::SBPLRecovery::initialized_
bool initialized_
Definition: sbpl_recovery.h:147
sbpl_recovery::SBPLRecovery::global_planner_
sbpl_lattice_planner::SBPLLatticePlanner global_planner_
Definition: sbpl_recovery.h:145
sbpl_recovery::SBPLRecovery::initialize
void initialize(std::string n, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Definition: sbpl_recovery.cpp:88
sbpl_recovery::SBPLRecovery::local_planner_
pose_follower::PoseFollower local_planner_
Definition: sbpl_recovery.h:146
sbpl_recovery::SBPLRecovery
Definition: sbpl_recovery.h:88
recovery_behavior.h
tf2_ros::Buffer
sbpl_lattice_planner.h
sbpl_recovery::SBPLRecovery::planning_attempts_
int planning_attempts_
Definition: sbpl_recovery.h:153
sbpl_recovery::SBPLRecovery::tf_
tf2_ros::Buffer * tf_
Definition: sbpl_recovery.h:144
sbpl_recovery::SBPLRecovery::sqDistance
double sqDistance(const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2)
Definition: sbpl_recovery.cpp:158
pose_follower::PoseFollower
sbpl_recovery::SBPLRecovery::plan_
nav_msgs::Path plan_
Definition: sbpl_recovery.h:151
sbpl_recovery::SBPLRecovery::use_local_frame_
bool use_local_frame_
Definition: sbpl_recovery.h:154
tf
sbpl_recovery::SBPLRecovery::controller_patience_
double controller_patience_
Definition: sbpl_recovery.h:152
sbpl_recovery::SBPLRecovery::runBehavior
void runBehavior()
Definition: sbpl_recovery.cpp:232
sbpl_recovery::SBPLRecovery::local_costmap_
costmap_2d::Costmap2DROS * local_costmap_
Definition: sbpl_recovery.h:143
costmap_2d::Costmap2DROS
nav_core::RecoveryBehavior
ros::Subscriber


sbpl_recovery
Author(s): Eitan Marder-Eppstein
autogenerated on Fri Aug 26 2022 02:17:55