twist_recovery.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  */
30 
39 #ifndef TWIST_RECOVERY_TWIST_RECOVERY_H
40 #define TWIST_RECOVERY_TWIST_RECOVERY_H
41 
45 #include <geometry_msgs/Pose2D.h>
46 
47 namespace twist_recovery
48 {
49 
53 {
54 public:
55 
57  TwistRecovery();
58 
60 
62  void initialize (std::string n, tf::TransformListener* tf,
63  costmap_2d::Costmap2DROS* global_costmap,
64  costmap_2d::Costmap2DROS* local_costmap);
65 
67  void runBehavior();
68 
69 private:
70 
71  geometry_msgs::Pose2D getCurrentLocalPose () const;
72  geometry_msgs::Twist scaleGivenAccelerationLimits (const geometry_msgs::Twist& twist, const double time_remaining) const;
73  double nonincreasingCostInterval (const geometry_msgs::Pose2D& current, const geometry_msgs::Twist& twist) const;
74  double normalizedPoseCost (const geometry_msgs::Pose2D& pose) const;
75  geometry_msgs::Twist transformTwist (const geometry_msgs::Pose2D& pose) const;
76 
80  std::string name_;
84 
85  // Memory owned by this object
86  // Mutable because footprintCost is not declared const
88 
89  geometry_msgs::Twist base_frame_twist_;
90 
91  double duration_;
98 
99 
100 };
101 
102 } // namespace twist_recovery
103 
104 #endif // include guard
geometry_msgs::Twist scaleGivenAccelerationLimits(const geometry_msgs::Twist &twist, const double time_remaining) const
void runBehavior()
Run the behavior.
double normalizedPoseCost(const geometry_msgs::Pose2D &pose) const
Return the cost of a pose, modified so that -1 does not equal infinity; instead 1e9 does...
geometry_msgs::Twist transformTwist(const geometry_msgs::Pose2D &pose) const
base_local_planner::CostmapModel * world_model_
geometry_msgs::Twist base_frame_twist_
costmap_2d::Costmap2DROS * global_costmap_
double nonincreasingCostInterval(const geometry_msgs::Pose2D &current, const geometry_msgs::Twist &twist) const
TwistRecovery()
Doesn&#39;t do anything: initialize is where the actual work happens.
tf::TransformListener * tf_
costmap_2d::Costmap2DROS * local_costmap_
geometry_msgs::Pose2D getCurrentLocalPose() const
void initialize(std::string n, tf::TransformListener *tf, costmap_2d::Costmap2DROS *global_costmap, costmap_2d::Costmap2DROS *local_costmap)
Initialize the parameters of the behavior.


twist_recovery
Author(s): Bhaskara Marthi
autogenerated on Tue Apr 2 2019 02:34:52