Nav2 Navigation Stack - kilted  kilted
ROS 2 Navigation Stack
velocity_polygon.hpp
1 // Copyright (c) 2023 Dexory
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
16 #define NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "geometry_msgs/msg/polygon_stamped.hpp"
23 #include "nav2_collision_monitor/polygon.hpp"
24 #include "nav2_collision_monitor/types.hpp"
25 #include "nav2_util/lifecycle_node.hpp"
26 #include "rclcpp/rclcpp.hpp"
27 #include "tf2_ros/buffer.h"
28 
29 namespace nav2_collision_monitor
30 {
31 
37 class VelocityPolygon : public Polygon
38 {
39 public:
46  const nav2_util::LifecycleNode::WeakPtr & node, const std::string & polygon_name,
47  const std::shared_ptr<tf2_ros::Buffer> tf_buffer, const std::string & base_frame_id,
48  const tf2::Duration & transform_tolerance);
52  virtual ~VelocityPolygon();
53 
61  bool getParameters(
62  std::string & /*polygon_sub_topic*/, std::string & polygon_pub_topic,
63  std::string & /*footprint_topic*/) override;
64 
69  void updatePolygon(const Velocity & cmd_vel_in) override;
70 
71 protected:
84  {
85  std::vector<Point> poly_;
86  std::string velocity_polygon_name_;
87  double linear_min_;
88  double linear_max_;
89  double theta_min_;
90  double theta_max_;
91  double direction_end_angle_;
92  double direction_start_angle_;
93  };
94 
101  bool isInRange(const Velocity & cmd_vel_in, const SubPolygonParameter & sub_polygon_param);
102 
103  // Clock
104  rclcpp::Clock::SharedPtr clock_;
105 
106  // Variables
110  std::vector<SubPolygonParameter> sub_polygons_;
111 }; // class VelocityPolygon
112 
113 } // namespace nav2_collision_monitor
114 
115 #endif // NAV2_COLLISION_MONITOR__VELOCITY_POLYGON_HPP_
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Definition: polygon.hpp:43
Velocity polygon class. This class contains all the points of the polygon and the expected condition ...
std::vector< SubPolygonParameter > sub_polygons_
Vector to store the parameters of the sub-polygon.
bool getParameters(std::string &, std::string &polygon_pub_topic, std::string &) override
Overridden getParameters function for VelocityPolygon parameters.
VelocityPolygon(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &polygon_name, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const std::string &base_frame_id, const tf2::Duration &transform_tolerance)
VelocityPolygon constructor.
bool isInRange(const Velocity &cmd_vel_in, const SubPolygonParameter &sub_polygon_param)
Check if the velocities and direction is in expected range.
virtual ~VelocityPolygon()
VelocityPolygon destructor.
void updatePolygon(const Velocity &cmd_vel_in) override
Overridden updatePolygon function for VelocityPolygon.
bool holonomic_
Flag to indicate if the robot is holonomic.
Custom struct to store the parameters of the sub-polygon.
Velocity for 2D model of motion.
Definition: types.hpp:25