route_speeds.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2017, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
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 Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from 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 <COPYRIGHT HOLDER> BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //
28 // *****************************************************************************
29 #ifndef SWRI_ROUTE_UTIL_ROUTE_SPEEDS_H_
30 #define SWRI_ROUTE_UTIL_ROUTE_SPEEDS_H_
31 
32 #include <marti_common_msgs/KeyValueArray.h>
33 #include <marti_nav_msgs/ObstacleArray.h>
34 #include <marti_nav_msgs/RouteSpeedArray.h>
36 #include <swri_route_util/route.h>
38 
39 namespace swri_route_util
40 {
42 {
49 
53 
54  // Filter constant used when estimating route curvature. Larger
55  // values result in smoother curvature estimates with fewer spikes.
57 
58 
60 
61  void loadFromRosParam(const ros::NodeHandle &pnh);
62 
63  void loadFromConfig(const marti_common_msgs::KeyValueArray &config);
64  void readToConfig(marti_common_msgs::KeyValueArray &config) const;
65 };
66 
68  marti_nav_msgs::RouteSpeedArray &speeds,
69  const Route &route,
70  const SpeedForCurvatureParameters &parameters);
71 
72 
74 {
79 
82  double max_speed_;
83  double min_speed_;
84 
86 
88 
89  void loadFromRosParam(const ros::NodeHandle &pnh);
90 };
91 
92 // ObstacleData is an intermediate representation for obstacles to
93 // avoid applying transforms and calculating radii repeatedly.
95 {
97  double radius;
98 
99  std::vector<tf::Vector3> polygon;
100 };
101 
102 
104 {
105  // True if the bounding circles touch but the actual polygons do not.
106  bool near;
107  // True if the actual polygons touch.
108  bool collision;
109  size_t route_index;
112  double distance;
113 };
114 
115 // Convert an obstacle array message into a ObstacleData by applying a
116 // transform and calculating the radius of each obstacle.
118  std::vector<ObstacleData> &obstacle_data,
119  const swri_transform_util::Transform g_route_from_obs,
120  const marti_nav_msgs::ObstacleArray &obstacles_msg);
121 
122 void speedsForObstacles(
123  marti_nav_msgs::RouteSpeedArray &speeds,
124  std::vector<DistanceReport> &reports,
125  const Route &route,
126  const marti_nav_msgs::RoutePosition &route_position,
127  const std::vector<ObstacleData> &obstacles,
128  const SpeedForObstaclesParameters &parameters);
129 } // namespace swri_route_util
130 #endif // SWRI_ROUTE_UTIL_ROUTE_SPEEDS_H_
void speedsForObstacles(marti_nav_msgs::RouteSpeedArray &speeds, std::vector< DistanceReport > &reports, const Route &route, const marti_nav_msgs::RoutePosition &route_position, const std::vector< ObstacleData > &obstacles, const SpeedForObstaclesParameters &parameters)
void readToConfig(marti_common_msgs::KeyValueArray &config) const
void loadFromRosParam(const ros::NodeHandle &pnh)
double max_lateral_accel_mss_
Maximum lateral acceleration in accel mode in m/s^2.
Definition: route_speeds.h:48
void speedsForCurvature(marti_nav_msgs::RouteSpeedArray &speeds, const Route &route, const SpeedForCurvatureParameters &parameters)
void generateObstacleData(std::vector< ObstacleData > &obstacle_data, const swri_transform_util::Transform g_route_from_obs, const marti_nav_msgs::ObstacleArray &obstacles_msg)
std::vector< tf::Vector3 > polygon
Definition: route_speeds.h:99
void loadFromConfig(const marti_common_msgs::KeyValueArray &config)
swri_math_util::Interpolation1D speed_curve_
Definition: route_speeds.h:52


swri_route_util
Author(s):
autogenerated on Fri Jun 7 2019 22:06:09