Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
vector_object_shapes.hpp
1 // Copyright (c) 2023 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_MAP_SERVER__VECTOR_OBJECT_SHAPES_HPP_
16 #define NAV2_MAP_SERVER__VECTOR_OBJECT_SHAPES_HPP_
17 
18 #include <memory>
19 #include <string>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "geometry_msgs/msg/polygon.hpp"
23 #include "geometry_msgs/msg/point32.hpp"
24 #include "nav_msgs/msg/occupancy_grid.hpp"
25 
26 #include "tf2_ros/buffer.hpp"
27 
28 #include "nav2_msgs/msg/polygon_object.hpp"
29 #include "nav2_msgs/msg/circle_object.hpp"
30 #include "nav2_ros_common/lifecycle_node.hpp"
31 
32 #include "nav2_map_server/vector_object_utils.hpp"
33 
34 namespace nav2_map_server
35 {
36 
38 enum ShapeType
39 {
40  UNKNOWN = 0,
41  POLYGON = 1,
42  CIRCLE = 2
43 };
44 
46 class Shape
47 {
48 public:
53  explicit Shape(const nav2::LifecycleNode::WeakPtr & node);
54 
58  virtual ~Shape();
59 
64  ShapeType getType();
65 
71  bool obtainShapeUUID(const std::string & shape_name, unsigned char * out_uuid);
72 
78  virtual int8_t getValue() const = 0;
79 
85  virtual std::string getFrameID() const = 0;
86 
92  virtual std::string getUUID() const = 0;
93 
100  virtual bool isUUID(const unsigned char * uuid) const = 0;
101 
107  virtual bool isFill() const = 0;
108 
115  virtual bool obtainParams(const std::string & shape_name) = 0;
116 
125  virtual bool toFrame(
126  const std::string & to_frame,
127  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
128  const double transform_tolerance) = 0;
129 
138  virtual void getBoundaries(double & min_x, double & min_y, double & max_x, double & max_y) = 0;
139 
147  virtual bool isPointInside(const double px, const double py) const = 0;
148 
155  virtual void putBorders(
156  nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type) = 0;
157 
158 protected:
160  ShapeType type_;
161 
163  nav2::LifecycleNode::WeakPtr node_;
164 };
165 
167 class Polygon : public Shape
168 {
169 public:
170  /*
171  * @brief Polygon class constructor
172  * @param node Vector Object server node pointer
173  * @note setParams()/obtainParams() should be called after to configure the shape
174  */
175  explicit Polygon(const nav2::LifecycleNode::WeakPtr & node);
176 
181  int8_t getValue() const;
182 
187  std::string getFrameID() const;
188 
193  std::string getUUID() const;
194 
200  bool isUUID(const unsigned char * uuid) const;
201 
206  bool isFill() const;
207 
213  bool obtainParams(const std::string & shape_name);
214 
219  nav2_msgs::msg::PolygonObject::SharedPtr getParams() const;
220 
225  bool setParams(const nav2_msgs::msg::PolygonObject::SharedPtr params);
226 
234  bool toFrame(
235  const std::string & to_frame,
236  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
237  const double transform_tolerance);
238 
246  void getBoundaries(double & min_x, double & min_y, double & max_x, double & max_y);
247 
254  bool isPointInside(const double px, const double py) const;
255 
261  void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type);
262 
263 protected:
268  bool checkConsistency();
269 
271  nav2_msgs::msg::PolygonObject::SharedPtr params_;
273  geometry_msgs::msg::Polygon::SharedPtr polygon_;
274 };
275 
277 class Circle : public Shape
278 {
279 public:
280  /*
281  * @brief Circle class constructor
282  * @param node Vector Object server node pointer
283  * @note setParams()/obtainParams() should be called after to configure the shape
284  */
285  explicit Circle(const nav2::LifecycleNode::WeakPtr & node);
286 
291  int8_t getValue() const;
292 
297  std::string getFrameID() const;
298 
303  std::string getUUID() const;
304 
310  bool isUUID(const unsigned char * uuid) const;
311 
316  bool isFill() const;
317 
323  bool obtainParams(const std::string & shape_name);
324 
329  nav2_msgs::msg::CircleObject::SharedPtr getParams() const;
330 
335  bool setParams(const nav2_msgs::msg::CircleObject::SharedPtr params);
336 
344  bool toFrame(
345  const std::string & to_frame,
346  const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
347  const double transform_tolerance);
348 
356  void getBoundaries(double & min_x, double & min_y, double & max_x, double & max_y);
357 
364  bool isPointInside(const double px, const double py) const;
365 
371  void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type);
372 
373 protected:
378  bool checkConsistency();
379 
389  bool centerToMap(
390  nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
391  unsigned int & mcx, unsigned int & mcy);
392 
400  void putPoint(
401  unsigned int mx, unsigned int my,
402  nav_msgs::msg::OccupancyGrid::SharedPtr map,
403  const OverlayType overlay_type);
404 
406  nav2_msgs::msg::CircleObject::SharedPtr params_;
408  geometry_msgs::msg::Point32::SharedPtr center_;
409 };
410 
411 } // namespace nav2_map_server
412 
413 #endif // NAV2_MAP_SERVER__VECTOR_OBJECT_SHAPES_HPP_
bool isUUID(const unsigned char *uuid) const
Checks whether the shape is equal to a given UUID.
bool toFrame(const std::string &to_frame, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const double transform_tolerance)
Transforms shape coordinates to a new frame.
int8_t getValue() const
Gets the value of the shape.
void putPoint(unsigned int mx, unsigned int my, nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Put Circle's point on map.
bool isPointInside(const double px, const double py) const
Is the point inside the shape.
std::string getUUID() const
Gets UUID of the shape.
void getBoundaries(double &min_x, double &min_y, double &max_x, double &max_y)
Gets shape box-boundaries.
std::string getFrameID() const
Gets frame ID of the shape.
bool centerToMap(nav_msgs::msg::OccupancyGrid::ConstSharedPtr map, unsigned int &mcx, unsigned int &mcy)
Converts circle center to map coordinates considering FP-accuracy losing on small values when using c...
bool isFill() const
Whether the shape to be filled or only its borders to be put on map.
nav2_msgs::msg::CircleObject::SharedPtr params_
Input circle parameters (could be in any frame)
bool setParams(const nav2_msgs::msg::CircleObject::SharedPtr params)
Tries to update Circle parameters.
void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Puts shape borders on map.
nav2_msgs::msg::CircleObject::SharedPtr getParams() const
Gets Circle parameters.
bool checkConsistency()
Checks that shape is consistent for further operation.
geometry_msgs::msg::Point32::SharedPtr center_
Circle center in the map's frame.
bool obtainParams(const std::string &shape_name)
Supporting routine obtaining ROS-parameters for the given vector object.
std::string getUUID() const
Gets UUID of the shape.
void getBoundaries(double &min_x, double &min_y, double &max_x, double &max_y)
Gets shape box-boundaries.
void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)
Puts shape borders on map.
bool isUUID(const unsigned char *uuid) const
Checks whether the shape is equal to a given UUID.
bool toFrame(const std::string &to_frame, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const double transform_tolerance)
Transforms shape coordinates to a new frame.
nav2_msgs::msg::PolygonObject::SharedPtr getParams() const
Gets Polygon parameters.
int8_t getValue() const
Gets the value of the shape.
bool setParams(const nav2_msgs::msg::PolygonObject::SharedPtr params)
Tries to update Polygon parameters.
std::string getFrameID() const
Gets frame ID of the shape.
nav2_msgs::msg::PolygonObject::SharedPtr params_
Input polygon parameters (could be in any frame)
bool checkConsistency()
Checks that shape is consistent for further operation.
bool isPointInside(const double px, const double py) const
Is the point inside the shape.
bool isFill() const
Whether the shape to be filled or only its borders to be put on map.
bool obtainParams(const std::string &shape_name)
Supporting routine obtaining ROS-parameters for the given vector object.
geometry_msgs::msg::Polygon::SharedPtr polygon_
Polygon in the map's frame.
Basic class, other vector objects to be inherited from.
virtual bool isFill() const =0
Whether the shape to be filled or only its borders to be put on map. Empty virtual method intended to...
virtual bool obtainParams(const std::string &shape_name)=0
Supporting routine obtaining ROS-parameters for the given vector object. Empty virtual method intende...
virtual void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type)=0
Puts shape borders on map. Empty virtual method intended to be used in child implementations.
bool obtainShapeUUID(const std::string &shape_name, unsigned char *out_uuid)
Supporting routine obtaining shape UUID from ROS-parameters for the given shape object.
virtual void getBoundaries(double &min_x, double &min_y, double &max_x, double &max_y)=0
Gets shape box-boundaries. Empty virtual method intended to be used in child implementations.
virtual bool isPointInside(const double px, const double py) const =0
Is the point inside the shape. Empty virtual method intended to be used in child implementations.
virtual bool toFrame(const std::string &to_frame, const std::shared_ptr< tf2_ros::Buffer > tf_buffer, const double transform_tolerance)=0
Transforms shape coordinates to a new frame. Empty virtual method intended to be used in child implem...
ShapeType type_
Type of shape.
ShapeType getType()
Returns type of the shape.
nav2::LifecycleNode::WeakPtr node_
VectorObjectServer node.
virtual std::string getFrameID() const =0
Gets frame ID of the shape. Empty virtual method intended to be used in child implementations.
virtual ~Shape()
Shape destructor.
Shape(const nav2::LifecycleNode::WeakPtr &node)
Shape basic class constructor.
virtual int8_t getValue() const =0
Gets the value of the shape. Empty virtual method intended to be used in child implementations.
virtual std::string getUUID() const =0
Gets UUID of the shape. Empty virtual method intended to be used in child implementations.
virtual bool isUUID(const unsigned char *uuid) const =0
Checks whether the shape is equal to a given UUID. Empty virtual method intended to be used in child ...