15 #ifndef NAV2_MAP_SERVER__VECTOR_OBJECT_SHAPES_HPP_
16 #define NAV2_MAP_SERVER__VECTOR_OBJECT_SHAPES_HPP_
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"
26 #include "tf2_ros/buffer.hpp"
28 #include "nav2_msgs/msg/polygon_object.hpp"
29 #include "nav2_msgs/msg/circle_object.hpp"
30 #include "nav2_ros_common/lifecycle_node.hpp"
32 #include "nav2_map_server/vector_object_utils.hpp"
34 namespace nav2_map_server
53 explicit Shape(
const nav2::LifecycleNode::WeakPtr & node);
71 bool obtainShapeUUID(
const std::string & shape_name,
unsigned char * out_uuid);
100 virtual bool isUUID(
const unsigned char * uuid)
const = 0;
126 const std::string & to_frame,
127 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
128 const double transform_tolerance) = 0;
138 virtual void getBoundaries(
double & min_x,
double & min_y,
double & max_x,
double & max_y) = 0;
156 nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type) = 0;
175 explicit Polygon(
const nav2::LifecycleNode::WeakPtr & node);
200 bool isUUID(
const unsigned char * uuid)
const;
219 nav2_msgs::msg::PolygonObject::SharedPtr
getParams()
const;
225 bool setParams(
const nav2_msgs::msg::PolygonObject::SharedPtr params);
235 const std::string & to_frame,
236 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
237 const double transform_tolerance);
246 void getBoundaries(
double & min_x,
double & min_y,
double & max_x,
double & max_y);
261 void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type);
271 nav2_msgs::msg::PolygonObject::SharedPtr
params_;
285 explicit Circle(
const nav2::LifecycleNode::WeakPtr & node);
310 bool isUUID(
const unsigned char * uuid)
const;
329 nav2_msgs::msg::CircleObject::SharedPtr
getParams()
const;
335 bool setParams(
const nav2_msgs::msg::CircleObject::SharedPtr params);
345 const std::string & to_frame,
346 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
347 const double transform_tolerance);
356 void getBoundaries(
double & min_x,
double & min_y,
double & max_x,
double & max_y);
371 void putBorders(nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type);
390 nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
391 unsigned int & mcx,
unsigned int & mcy);
401 unsigned int mx,
unsigned int my,
402 nav_msgs::msg::OccupancyGrid::SharedPtr map,
403 const OverlayType overlay_type);
406 nav2_msgs::msg::CircleObject::SharedPtr
params_;
408 geometry_msgs::msg::Point32::SharedPtr
center_;
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 ...