rotate_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 ROTATE_RECOVERY_ROTATE_RECOVERY_H
38 #define ROTATE_RECOVERY_ROTATE_RECOVERY_H
41 #include <tf2_ros/buffer.h>
43 #include <string>
44 
45 namespace rotate_recovery
46 {
52 {
53 public:
58 
66  void initialize(std::string name, tf2_ros::Buffer*,
68 
72  void runBehavior();
73 
78 
79 private:
81  bool initialized_;
84 };
85 }; // namespace rotate_recovery
86 #endif // ROTATE_RECOVERY_ROTATE_RECOVERY_H
rotate_recovery::RotateRecovery::RotateRecovery
RotateRecovery()
Constructor, make sure to call initialize in addition to actually initialize the object.
Definition: rotate_recovery.cpp:89
rotate_recovery
Definition: rotate_recovery.h:45
rotate_recovery::RotateRecovery::runBehavior
void runBehavior()
Run the RotateRecovery recovery behavior.
Definition: rotate_recovery.cpp:128
rotate_recovery::RotateRecovery::acc_lim_th_
double acc_lim_th_
Definition: rotate_recovery.h:117
rotate_recovery::RotateRecovery::initialize
void initialize(std::string name, tf2_ros::Buffer *, costmap_2d::Costmap2DROS *, costmap_2d::Costmap2DROS *local_costmap)
Initialization function for the RotateRecovery recovery behavior.
Definition: rotate_recovery.cpp:93
rotate_recovery::RotateRecovery::min_rotational_vel_
double min_rotational_vel_
Definition: rotate_recovery.h:117
rotate_recovery::RotateRecovery::local_costmap_
costmap_2d::Costmap2DROS * local_costmap_
Definition: rotate_recovery.h:115
buffer.h
rotate_recovery::RotateRecovery::world_model_
base_local_planner::CostmapModel * world_model_
Definition: rotate_recovery.h:118
costmap_2d_ros.h
rotate_recovery::RotateRecovery::~RotateRecovery
~RotateRecovery()
Destructor for the rotate recovery behavior.
Definition: rotate_recovery.cpp:123
rotate_recovery::RotateRecovery::max_rotational_vel_
double max_rotational_vel_
Definition: rotate_recovery.h:117
base_local_planner::CostmapModel
rotate_recovery::RotateRecovery::frequency_
double frequency_
Definition: rotate_recovery.h:117
rotate_recovery::RotateRecovery::sim_granularity_
double sim_granularity_
Definition: rotate_recovery.h:117
costmap_model.h
recovery_behavior.h
rotate_recovery::RotateRecovery::initialized_
bool initialized_
Definition: rotate_recovery.h:116
tf2_ros::Buffer
rotate_recovery::RotateRecovery::tolerance_
double tolerance_
Definition: rotate_recovery.h:117
rotate_recovery::RotateRecovery
A recovery behavior that rotates the robot in-place to attempt to clear out space.
Definition: rotate_recovery.h:86
costmap_2d::Costmap2DROS
nav_core::RecoveryBehavior


rotate_recovery
Author(s): Eitan Marder-Eppstein, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:43