15 #include "nav2_map_server/vector_object_shapes.hpp"
17 #include <uuid/uuid.h>
24 #include "geometry_msgs/msg/pose_stamped.hpp"
26 #include "nav2_util/occ_grid_utils.hpp"
27 #include "nav2_util/occ_grid_values.hpp"
28 #include "nav2_util/geometry_utils.hpp"
29 #include "nav2_util/raytrace_line_2d.hpp"
30 #include "nav2_util/robot_utils.hpp"
32 namespace nav2_map_server
38 : type_(UNKNOWN), node_(node)
51 auto node =
node_.lock();
53 throw std::runtime_error{
"Failed to lock node"};
58 std::string uuid_str = nav2::declare_or_get_parameter<std::string>(
59 node, shape_name +
".uuid", rclcpp::PARAMETER_STRING);
60 if (uuid_parse(uuid_str.c_str(), out_uuid) != 0) {
63 "[%s] Can not parse UUID string for shape: %s",
64 shape_name.c_str(), uuid_str.c_str());
67 }
catch (
const std::exception &) {
69 uuid_generate(out_uuid);
72 uuid_unparse(out_uuid, uuid_str);
75 "[%s] No UUID is specified for shape. Generating a new one: %s",
76 shape_name.c_str(), uuid_str);
85 const nav2::LifecycleNode::WeakPtr & node)
98 return params_->header.frame_id;
103 return unparseUUID(
params_->uuid.uuid.data());
108 return uuid_compare(
params_->uuid.uuid.data(), uuid) == 0;
118 auto node =
node_.lock();
120 throw std::runtime_error{
"Failed to lock node"};
124 params_ = std::make_shared<nav2_msgs::msg::PolygonObject>();
127 polygon_ = std::make_shared<geometry_msgs::msg::Polygon>();
130 params_->header.frame_id = nav2::declare_or_get_parameter(
131 node, shape_name +
".frame_id", std::string{
"map"});
132 params_->value = nav2::declare_or_get_parameter(
133 node, shape_name +
".value",
static_cast<int>(nav2_util::OCC_GRID_OCCUPIED));
134 params_->closed = nav2::declare_or_get_parameter(
135 node, shape_name +
".closed",
true);
137 std::vector<double> poly_row;
139 poly_row = nav2::declare_or_get_parameter<std::vector<double>>(
140 node, shape_name +
".points", rclcpp::PARAMETER_DOUBLE_ARRAY);
141 }
catch (
const std::exception & ex) {
144 "[%s] Error while getting polygon parameters: %s",
145 shape_name.c_str(), ex.what());
149 if (poly_row.size() < 6 || poly_row.size() % 2 != 0) {
152 "[%s] Polygon has incorrect points description",
158 geometry_msgs::msg::Point32 point;
160 for (
double val : poly_row) {
165 params_->points.push_back(point);
187 polygon_ = std::make_shared<geometry_msgs::msg::Polygon>();
192 if (uuid_is_null(
params_->uuid.uuid.data())) {
193 uuid_generate(
params_->uuid.uuid.data());
200 const std::string & to_frame,
201 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
202 const double transform_tolerance)
204 geometry_msgs::msg::PoseStamped from_pose, to_pose;
205 from_pose.header =
params_->header;
206 for (
unsigned int i = 0; i <
params_->points.size(); i++) {
207 from_pose.pose.position.x =
params_->points[i].x;
208 from_pose.pose.position.y =
params_->points[i].y;
209 from_pose.pose.position.z =
params_->points[i].z;
211 nav2_util::transformPoseInTargetFrame(
212 from_pose, to_pose, *tf_buffer, to_frame, transform_tolerance))
214 polygon_->points[i].x = to_pose.pose.position.x;
215 polygon_->points[i].y = to_pose.pose.position.y;
216 polygon_->points[i].z = to_pose.pose.position.z;
227 min_x = std::numeric_limits<double>::max();
228 min_y = std::numeric_limits<double>::max();
229 max_x = std::numeric_limits<double>::lowest();
230 max_y = std::numeric_limits<double>::lowest();
232 for (
auto point :
polygon_->points) {
233 min_x = std::min(min_x,
static_cast<double>(point.x));
234 min_y = std::min(min_y,
static_cast<double>(point.y));
235 max_x = std::max(max_x,
static_cast<double>(point.x));
236 max_y = std::max(max_y,
static_cast<double>(point.y));
242 return nav2_util::geometry_utils::isPointInsidePolygon(px, py,
polygon_->points);
246 nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type)
248 unsigned int mx0, my0, mx1, my1;
250 auto node =
node_.lock();
252 throw std::runtime_error{
"Failed to lock node"};
255 if (!nav2_util::worldToMap(map,
polygon_->points[0].x,
polygon_->points[0].y, mx1, my1)) {
258 "[UUID: %s] Can not convert (%f, %f) point to map",
264 for (
unsigned int i = 1; i <
polygon_->points.size(); i++) {
267 if (!nav2_util::worldToMap(map,
polygon_->points[i].x,
polygon_->points[i].y, mx1, my1)) {
270 "[UUID: %s] Can not convert (%f, %f) point to map",
274 nav2_util::raytraceLine(ma, mx0, my0, mx1, my1, map->info.width);
280 if (
params_->points.size() < 3) {
281 auto node =
node_.lock();
283 throw std::runtime_error{
"Failed to lock node"};
288 "[UUID: %s] Polygon has incorrect number of vertices: %li",
299 const nav2::LifecycleNode::WeakPtr & node)
312 return params_->header.frame_id;
317 return unparseUUID(
params_->uuid.uuid.data());
322 return uuid_compare(
params_->uuid.uuid.data(), uuid) == 0;
332 auto node =
node_.lock();
334 throw std::runtime_error{
"Failed to lock node"};
338 params_ = std::make_shared<nav2_msgs::msg::CircleObject>();
341 center_ = std::make_shared<geometry_msgs::msg::Point32>();
344 params_->header.frame_id = nav2::declare_or_get_parameter(
345 node, shape_name +
".frame_id", std::string{
"map"});
346 params_->value = nav2::declare_or_get_parameter(
347 node, shape_name +
".value",
static_cast<int>(nav2_util::OCC_GRID_OCCUPIED));
348 params_->fill = nav2::declare_or_get_parameter(
349 node, shape_name +
".fill",
true);
351 std::vector<double> center_row;
353 center_row = nav2::declare_or_get_parameter<std::vector<double>>(
354 node, shape_name +
".center", rclcpp::PARAMETER_DOUBLE_ARRAY);
355 params_->radius = nav2::declare_or_get_parameter<double>(
356 node, shape_name +
".radius", rclcpp::PARAMETER_DOUBLE);
360 "[%s] Circle has incorrect radius less than zero",
364 }
catch (
const std::exception & ex) {
367 "[%s] Error while getting circle parameters: %s",
368 shape_name.c_str(), ex.what());
372 if (center_row.size() != 2) {
375 "[%s] Circle has incorrect center description",
381 params_->center.x = center_row[0];
382 params_->center.y = center_row[1];
400 center_ = std::make_shared<geometry_msgs::msg::Point32>();
405 if (uuid_is_null(
params_->uuid.uuid.data())) {
406 uuid_generate(
params_->uuid.uuid.data());
413 const std::string & to_frame,
414 const std::shared_ptr<tf2_ros::Buffer> tf_buffer,
415 const double transform_tolerance)
417 geometry_msgs::msg::PoseStamped from_pose, to_pose;
418 from_pose.header =
params_->header;
419 from_pose.pose.position.x =
params_->center.x;
420 from_pose.pose.position.y =
params_->center.y;
421 from_pose.pose.position.z =
params_->center.z;
423 nav2_util::transformPoseInTargetFrame(
424 from_pose, to_pose, *tf_buffer, to_frame, transform_tolerance))
426 center_->x = to_pose.pose.position.x;
427 center_->y = to_pose.pose.position.y;
428 center_->z = to_pose.pose.position.z;
451 nav_msgs::msg::OccupancyGrid::SharedPtr map,
const OverlayType overlay_type)
453 unsigned int mcx, mcy;
463 const int r =
static_cast<int>(std::round(
params_->radius / map->info.resolution));
473 putPoint(mcx + x, mcy + y, map, overlay_type);
474 putPoint(mcx + y, mcy + x, map, overlay_type);
475 putPoint(mcx - x + 1, mcy + y, map, overlay_type);
476 putPoint(mcx + y, mcy - x + 1, map, overlay_type);
477 putPoint(mcx - x + 1, mcy - y + 1, map, overlay_type);
478 putPoint(mcx - y + 1, mcy - x + 1, map, overlay_type);
479 putPoint(mcx + x, mcy - y + 1, map, overlay_type);
480 putPoint(mcx - y + 1, mcy + x, map, overlay_type);
492 putPoint(mcx + x, mcy + y, map, overlay_type);
493 putPoint(mcx - x + 1, mcy + y, map, overlay_type);
494 putPoint(mcx - x + 1, mcy - y + 1, map, overlay_type);
495 putPoint(mcx + x, mcy - y + 1, map, overlay_type);
502 auto node =
node_.lock();
504 throw std::runtime_error{
"Failed to lock node"};
509 "[UUID: %s] Circle has incorrect radius less than zero",
517 nav_msgs::msg::OccupancyGrid::ConstSharedPtr map,
518 unsigned int & mcx,
unsigned int & mcy)
520 auto node =
node_.lock();
522 throw std::runtime_error{
"Failed to lock node"};
526 if (
center_->x < map->info.origin.position.x ||
center_->y < map->info.origin.position.y) {
529 "[UUID: %s] Can not convert (%f, %f) circle center to map",
536 mcx =
static_cast<unsigned int>(
537 std::round((
center_->x - map->info.origin.position.x) / map->info.resolution)) - 1;
538 mcy =
static_cast<unsigned int>(
539 std::round((
center_->y - map->info.origin.position.y) / map->info.resolution)) - 1;
540 if (mcx >= map->info.width || mcy >= map->info.height) {
543 "[UUID: %s] Can not convert (%f, %f) point to map",
552 unsigned int mx,
unsigned int my,
553 nav_msgs::msg::OccupancyGrid::SharedPtr map,
554 const OverlayType overlay_type)
556 processCell(map, my * map->info.width + mx,
params_->value, overlay_type);
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.
Functor class used in raytraceLine algorithm.
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.
bool obtainShapeUUID(const std::string &shape_name, unsigned char *out_uuid)
Supporting routine obtaining shape UUID from ROS-parameters for the given shape object.
ShapeType type_
Type of shape.
ShapeType getType()
Returns type of the shape.
nav2::LifecycleNode::WeakPtr node_
VectorObjectServer node.
virtual ~Shape()
Shape destructor.
Shape(const nav2::LifecycleNode::WeakPtr &node)
Shape basic class constructor.