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 #include <geometry_msgs/PoseStamped.h>
47 #include <geometry_msgs/Twist.h>
48 #include <tf2_ros/buffer.h>
49 
50 namespace twist_recovery
51 {
52 
56 {
57 public:
58 
60  TwistRecovery();
61 
63 
65  void initialize (std::string n, tf2_ros::Buffer* tf,
66  costmap_2d::Costmap2DROS* global_costmap,
67  costmap_2d::Costmap2DROS* local_costmap);
68 
70  void runBehavior();
71 
72 private:
73 
74  geometry_msgs::Pose2D getCurrentLocalPose () const;
75  geometry_msgs::Twist scaleGivenAccelerationLimits (const geometry_msgs::Twist& twist, const double time_remaining) const;
76  double nonincreasingCostInterval (const geometry_msgs::Pose2D& current, const geometry_msgs::Twist& twist) const;
77  double normalizedPoseCost (const geometry_msgs::Pose2D& pose) const;
78  geometry_msgs::Twist transformTwist (const geometry_msgs::Pose2D& pose) const;
79 
83  std::string name_;
87 
88  // Memory owned by this object
89  // Mutable because footprintCost is not declared const
91 
92  geometry_msgs::Twist base_frame_twist_;
93 
94  double duration_;
101 
102 
103 };
104 
105 } // namespace twist_recovery
106 
107 #endif // include guard
void runBehavior()
Run the behavior.
geometry_msgs::Twist transformTwist(const geometry_msgs::Pose2D &pose) const
geometry_msgs::Twist scaleGivenAccelerationLimits(const geometry_msgs::Twist &twist, const double time_remaining) const
base_local_planner::CostmapModel * world_model_
geometry_msgs::Twist base_frame_twist_
costmap_2d::Costmap2DROS * global_costmap_
TwistRecovery()
Doesn&#39;t do anything: initialize is where the actual work happens.
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...
double nonincreasingCostInterval(const geometry_msgs::Pose2D &current, const geometry_msgs::Twist &twist) const
costmap_2d::Costmap2DROS * local_costmap_
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.
geometry_msgs::Pose2D getCurrentLocalPose() const


twist_recovery
Author(s): Bhaskara Marthi
autogenerated on Sat Aug 27 2022 02:54:24