|
Nav2 Navigation Stack - rolling
main
ROS 2 Navigation Stack
|
#include <nav2_map_server/include/nav2_map_server/vector_object_shapes.hpp>


Public Member Functions | |
| Circle (const nav2::LifecycleNode::WeakPtr &node) | |
| int8_t | getValue () const |
| Gets the value of the shape. More... | |
| std::string | getFrameID () const |
| Gets frame ID of the shape. More... | |
| std::string | getUUID () const |
| Gets UUID of the shape. More... | |
| bool | isUUID (const unsigned char *uuid) const |
| Checks whether the shape is equal to a given UUID. More... | |
| bool | isFill () const |
| Whether the shape to be filled or only its borders to be put on map. More... | |
| bool | obtainParams (const std::string &shape_name) |
| Supporting routine obtaining ROS-parameters for the given vector object. More... | |
| nav2_msgs::msg::CircleObject::SharedPtr | getParams () const |
| Gets Circle parameters. More... | |
| bool | setParams (const nav2_msgs::msg::CircleObject::SharedPtr params) |
| Tries to update Circle parameters. More... | |
| 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. More... | |
| void | getBoundaries (double &min_x, double &min_y, double &max_x, double &max_y) |
| Gets shape box-boundaries. More... | |
| bool | isPointInside (const double px, const double py) const |
| Is the point inside the shape. More... | |
| void | putBorders (nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type) |
| Puts shape borders on map. More... | |
Public Member Functions inherited from nav2_map_server::Shape | |
| Shape (const nav2::LifecycleNode::WeakPtr &node) | |
| Shape basic class constructor. More... | |
| virtual | ~Shape () |
| Shape destructor. | |
| ShapeType | getType () |
| Returns type of the shape. More... | |
| bool | obtainShapeUUID (const std::string &shape_name, unsigned char *out_uuid) |
| Supporting routine obtaining shape UUID from ROS-parameters for the given shape object. More... | |
Protected Member Functions | |
| bool | checkConsistency () |
| Checks that shape is consistent for further operation. More... | |
| 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 conventional nav2_util::worldToMap() approach. More... | |
| void | putPoint (unsigned int mx, unsigned int my, nav_msgs::msg::OccupancyGrid::SharedPtr map, const OverlayType overlay_type) |
| Put Circle's point on map. More... | |
Protected Attributes | |
| nav2_msgs::msg::CircleObject::SharedPtr | params_ |
| Input circle parameters (could be in any frame) | |
| geometry_msgs::msg::Point32::SharedPtr | center_ |
| Circle center in the map's frame. | |
Protected Attributes inherited from nav2_map_server::Shape | |
| ShapeType | type_ |
| Type of shape. | |
| nav2::LifecycleNode::WeakPtr | node_ |
| VectorObjectServer node. | |
Circle shape class.
Definition at line 277 of file vector_object_shapes.hpp.
|
protected |
Converts circle center to map coordinates considering FP-accuracy losing on small values when using conventional nav2_util::worldToMap() approach.
| map | Map pointer |
| mcx | Output X-coordinate of associated circle center on map |
| mcy | Output Y-coordinate of associated circle center on map |
Definition at line 516 of file vector_object_shapes.cpp.
References center_, getUUID(), and nav2_map_server::Shape::node_.
Referenced by putBorders().


|
protected |
Checks that shape is consistent for further operation.
Definition at line 499 of file vector_object_shapes.cpp.
References getUUID(), nav2_map_server::Shape::node_, and params_.
Referenced by setParams().


|
virtual |
Gets shape box-boundaries.
| min_x | output min X-boundary of shape |
| min_y | output min Y-boundary of shape |
| max_x | output max X-boundary of shape |
| max_y | output max Y-boundary of shape |
Implements nav2_map_server::Shape.
Definition at line 436 of file vector_object_shapes.cpp.
|
virtual |
Gets frame ID of the shape.
Implements nav2_map_server::Shape.
Definition at line 310 of file vector_object_shapes.cpp.
References params_.
| nav2_msgs::msg::CircleObject::SharedPtr nav2_map_server::Circle::getParams | ( | ) | const |
Gets Circle parameters.
Definition at line 390 of file vector_object_shapes.cpp.
References params_.
|
virtual |
Gets UUID of the shape.
Implements nav2_map_server::Shape.
Definition at line 315 of file vector_object_shapes.cpp.
References params_.
Referenced by centerToMap(), and checkConsistency().

|
virtual |
Gets the value of the shape.
Implements nav2_map_server::Shape.
Definition at line 305 of file vector_object_shapes.cpp.
References params_.
|
virtual |
Whether the shape to be filled or only its borders to be put on map.
Implements nav2_map_server::Shape.
Definition at line 325 of file vector_object_shapes.cpp.
References params_.
|
virtual |
Is the point inside the shape.
| px | X-coordinate of the given point to check |
| py | Y-coordinate of the given point to check |
Implements nav2_map_server::Shape.
Definition at line 444 of file vector_object_shapes.cpp.
|
virtual |
Checks whether the shape is equal to a given UUID.
| uuid | Given UUID to check with |
Implements nav2_map_server::Shape.
Definition at line 320 of file vector_object_shapes.cpp.
References params_.
|
virtual |
Supporting routine obtaining ROS-parameters for the given vector object.
| shape_name | Name of the shape |
Implements nav2_map_server::Shape.
Definition at line 330 of file vector_object_shapes.cpp.
References center_, nav2_map_server::Shape::node_, nav2_map_server::Shape::obtainShapeUUID(), and params_.

|
virtual |
Puts shape borders on map.
| map | Output map pointer |
| overlay_type | Overlay type |
Implements nav2_map_server::Shape.
Definition at line 450 of file vector_object_shapes.cpp.
References centerToMap(), params_, and putPoint().

|
inlineprotected |
Put Circle's point on map.
| mx | X-coordinate of given point |
| my | Y-coordinate of given point |
| map | Output map pointer |
| overlay_type | Overlay type |
Definition at line 551 of file vector_object_shapes.cpp.
References params_.
Referenced by putBorders().

| bool nav2_map_server::Circle::setParams | ( | const nav2_msgs::msg::CircleObject::SharedPtr | params | ) |
Tries to update Circle parameters.
Definition at line 395 of file vector_object_shapes.cpp.
References center_, checkConsistency(), and params_.

|
virtual |
Transforms shape coordinates to a new frame.
| to_frame | Frame ID to transform to |
| tf_buffer | TF buffer to use for the transformation |
| transform_tolerance | Transform tolerance |
Implements nav2_map_server::Shape.
Definition at line 412 of file vector_object_shapes.cpp.