Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
circle.hpp
1 // Copyright (c) 2022 Samsung R&D Institute Russia
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__CIRCLE_HPP_
16 #define NAV2_COLLISION_MONITOR__CIRCLE_HPP_
17 
18 #include <memory>
19 #include <vector>
20 #include <string>
21 
22 #include "std_msgs/msg/float32.hpp"
23 
24 #include "nav2_collision_monitor/polygon.hpp"
25 
26 namespace nav2_collision_monitor
27 {
28 
34 class Circle : public Polygon
35 {
36 public:
45  Circle(
46  const nav2::LifecycleNode::WeakPtr & node,
47  const std::string & polygon_name,
48  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
49  const std::string & base_frame_id,
50  const tf2::Duration & transform_tolerance);
54  ~Circle();
55 
61  void getPolygon(std::vector<Point> & poly) const override;
62 
69  int getPointsInside(const std::vector<Point> & points) const override;
70 
75  bool isShapeSet() override;
76 
77 protected:
86  bool getParameters(
87  std::string & polygon_sub_topic,
88  std::string & polygon_pub_topic,
89  std::string & footprint_topic) override;
90 
96  void createSubscription(std::string & polygon_sub_topic) override;
97 
102  void updatePolygon(double radius);
103 
108  void radiusCallback(std_msgs::msg::Float32::ConstSharedPtr msg);
109 
110 
111  // ----- Variables -----
112 
114  double radius_;
116  double radius_squared_ = -1.0;
118  nav2::Subscription<std_msgs::msg::Float32>::SharedPtr radius_sub_;
119 }; // class Circle
120 
121 } // namespace nav2_collision_monitor
122 
123 #endif // NAV2_COLLISION_MONITOR__CIRCLE_HPP_
Circle shape implementation. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while ...
Definition: circle.hpp:35
int getPointsInside(const std::vector< Point > &points) const override
Gets number of points inside circle.
Definition: circle.cpp:61
bool getParameters(std::string &polygon_sub_topic, std::string &polygon_pub_topic, std::string &footprint_topic) override
Supporting routine obtaining polygon-specific ROS-parameters.
Definition: circle.cpp:82
void getPolygon(std::vector< Point > &poly) const override
Gets polygon points, approximated to the circle. To be used in visualization purposes.
Definition: circle.cpp:42
double radius_squared_
(radius * radius) value. Stored for optimization.
Definition: circle.hpp:116
void radiusCallback(std_msgs::msg::Float32::ConstSharedPtr msg)
Dynamic circle radius callback.
Definition: circle.cpp:171
bool isShapeSet() override
Returns true if circle radius is set. Otherwise, prints a warning and returns false.
Definition: circle.cpp:73
nav2::Subscription< std_msgs::msg::Float32 >::SharedPtr radius_sub_
Radius subscription.
Definition: circle.hpp:118
Circle(const nav2::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)
Circle class constructor.
Definition: circle.cpp:26
void updatePolygon(double radius)
Updates polygon from radius value.
Definition: circle.cpp:152
~Circle()
Circle class destructor.
Definition: circle.cpp:37
double radius_
Radius of the circle.
Definition: circle.hpp:114
void createSubscription(std::string &polygon_sub_topic) override
Creates polygon or radius topic subscription.
Definition: circle.cpp:129
Basic polygon shape class. For STOP/SLOWDOWN/LIMIT model it represents zone around the robot while fo...
Definition: polygon.hpp:43