move_slow_and_clear.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 MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_
38 #define MOVE_SLOW_AND_CLEAR_MOVE_SLOW_AND_CLEAR_H_
39 
40 #include <ros/ros.h>
43 #include <boost/thread.hpp>
44 #include <dynamic_reconfigure/Reconfigure.h>
45 
47 {
49  {
50  public:
53 
55  void initialize (std::string n, tf2_ros::Buffer* tf,
56  costmap_2d::Costmap2DROS* global_costmap,
57  costmap_2d::Costmap2DROS* local_costmap);
58 
60  void runBehavior();
61 
62  private:
63  void setRobotSpeed(double trans_speed, double rot_speed);
64  void distanceCheck(const ros::TimerEvent& e);
65  double getSqDistance();
66 
67  void removeSpeedLimit();
68 
72  bool initialized_;
77  geometry_msgs::PoseStamped speed_limit_pose_;
78  boost::thread* remove_limit_thread_;
79  boost::mutex mutex_;
80  bool limit_set_;
82  };
83 };
84 
85 #endif
move_slow_and_clear::MoveSlowAndClear::local_costmap_
costmap_2d::Costmap2DROS * local_costmap_
Definition: move_slow_and_clear.h:141
move_slow_and_clear::MoveSlowAndClear
Definition: move_slow_and_clear.h:83
move_slow_and_clear::MoveSlowAndClear::max_trans_param_name_
std::string max_trans_param_name_
Definition: move_slow_and_clear.h:145
move_slow_and_clear::MoveSlowAndClear::limited_trans_speed_
double limited_trans_speed_
Definition: move_slow_and_clear.h:144
move_slow_and_clear::MoveSlowAndClear::distance_check_timer_
ros::Timer distance_check_timer_
Definition: move_slow_and_clear.h:146
move_slow_and_clear::MoveSlowAndClear::~MoveSlowAndClear
~MoveSlowAndClear()
Definition: move_slow_and_clear.cpp:83
move_slow_and_clear::MoveSlowAndClear::limit_set_
bool limit_set_
Definition: move_slow_and_clear.h:150
move_slow_and_clear::MoveSlowAndClear::getSqDistance
double getSqDistance()
Definition: move_slow_and_clear.cpp:191
ros.h
move_slow_and_clear::MoveSlowAndClear::limited_rot_speed_
double limited_rot_speed_
Definition: move_slow_and_clear.h:144
move_slow_and_clear::MoveSlowAndClear::limited_distance_
double limited_distance_
Definition: move_slow_and_clear.h:143
costmap_2d_ros.h
move_slow_and_clear::MoveSlowAndClear::speed_limit_pose_
geometry_msgs::PoseStamped speed_limit_pose_
Definition: move_slow_and_clear.h:147
move_slow_and_clear::MoveSlowAndClear::removeSpeedLimit
void removeSpeedLimit()
Definition: move_slow_and_clear.cpp:221
move_slow_and_clear::MoveSlowAndClear::planner_nh_
ros::NodeHandle planner_nh_
Definition: move_slow_and_clear.h:139
move_slow_and_clear::MoveSlowAndClear::initialize
void initialize(std::string n, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.
Definition: move_slow_and_clear.cpp:88
move_slow_and_clear::MoveSlowAndClear::setRobotSpeed
void setRobotSpeed(double trans_speed, double rot_speed)
Definition: move_slow_and_clear.cpp:228
move_slow_and_clear::MoveSlowAndClear::old_trans_speed_
double old_trans_speed_
Definition: move_slow_and_clear.h:144
move_slow_and_clear::MoveSlowAndClear::mutex_
boost::mutex mutex_
Definition: move_slow_and_clear.h:149
move_slow_and_clear::MoveSlowAndClear::initialized_
bool initialized_
Definition: move_slow_and_clear.h:142
recovery_behavior.h
ros::ServiceClient
tf2_ros::Buffer
ros::TimerEvent
move_slow_and_clear::MoveSlowAndClear::private_nh_
ros::NodeHandle private_nh_
Definition: move_slow_and_clear.h:139
move_slow_and_clear::MoveSlowAndClear::remove_limit_thread_
boost::thread * remove_limit_thread_
Definition: move_slow_and_clear.h:148
move_slow_and_clear::MoveSlowAndClear::planner_dynamic_reconfigure_service_
ros::ServiceClient planner_dynamic_reconfigure_service_
Definition: move_slow_and_clear.h:151
move_slow_and_clear::MoveSlowAndClear::old_rot_speed_
double old_rot_speed_
Definition: move_slow_and_clear.h:144
move_slow_and_clear::MoveSlowAndClear::global_costmap_
costmap_2d::Costmap2DROS * global_costmap_
Definition: move_slow_and_clear.h:140
move_slow_and_clear::MoveSlowAndClear::distanceCheck
void distanceCheck(const ros::TimerEvent &e)
Definition: move_slow_and_clear.cpp:204
move_slow_and_clear::MoveSlowAndClear::max_rot_param_name_
std::string max_rot_param_name_
Definition: move_slow_and_clear.h:145
move_slow_and_clear::MoveSlowAndClear::clearing_distance_
double clearing_distance_
Definition: move_slow_and_clear.h:143
move_slow_and_clear::MoveSlowAndClear::MoveSlowAndClear
MoveSlowAndClear()
Definition: move_slow_and_clear.cpp:80
tf
ros::Timer
costmap_2d::Costmap2DROS
move_slow_and_clear::MoveSlowAndClear::runBehavior
void runBehavior()
Run the behavior.
Definition: move_slow_and_clear.cpp:110
nav_core::RecoveryBehavior
ros::NodeHandle
move_slow_and_clear
Definition: move_slow_and_clear.h:46


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