15 #include "nav2_map_server/vector_object_server.hpp"
24 #include "rclcpp/create_timer.hpp"
26 #include "tf2_ros/create_timer_ros.hpp"
28 #include "nav2_util/occ_grid_utils.hpp"
29 #include "nav2_util/occ_grid_values.hpp"
31 using namespace std::placeholders;
33 namespace nav2_map_server
36 VectorObjectServer::VectorObjectServer(
const rclcpp::NodeOptions & options)
37 : nav2::LifecycleNode(
"vector_object_server",
"", options), process_map_(false)
43 RCLCPP_INFO(get_logger(),
"Configuring");
46 tf_buffer_ = std::make_shared<tf2_ros::Buffer>(this->get_clock());
47 auto timer_interface = std::make_shared<tf2_ros::CreateTimerROS>(
48 this->get_node_base_interface(),
49 this->get_node_timers_interface());
50 tf_buffer_->setCreateTimerInterface(timer_interface);
55 return nav2::CallbackReturn::FAILURE;
58 map_pub_ = create_publisher<nav_msgs::msg::OccupancyGrid>(
74 return nav2::CallbackReturn::SUCCESS;
80 RCLCPP_INFO(get_logger(),
"Activating");
91 return nav2::CallbackReturn::SUCCESS;
97 RCLCPP_INFO(get_logger(),
"Deactivating");
110 return nav2::CallbackReturn::SUCCESS;
116 RCLCPP_INFO(get_logger(),
"Cleaning up");
130 return nav2::CallbackReturn::SUCCESS;
136 RCLCPP_INFO(get_logger(),
"Shutting down");
137 return nav2::CallbackReturn::SUCCESS;
145 map_topic_ = nav2::declare_or_get_parameter(node,
"map_topic", std::string{
"vo_map"});
146 global_frame_id_ = nav2::declare_or_get_parameter(node,
"global_frame_id", std::string{
"map"});
147 resolution_ = nav2::declare_or_get_parameter(node,
"resolution", 0.05);
148 default_value_ = nav2::declare_or_get_parameter(node,
"default_value",
149 static_cast<int>(nav2_util::OCC_GRID_UNKNOWN));
150 overlay_type_ =
static_cast<OverlayType
>(nav2::declare_or_get_parameter(node,
"overlay_type",
151 static_cast<int>(OverlayType::OVERLAY_SEQ)));
152 update_frequency_ = nav2::declare_or_get_parameter(node,
"update_frequency", 1.0);
156 auto shape_names = nav2::declare_or_get_parameter(node,
"shapes", std::vector<std::string>());
157 for (std::string shape_name : shape_names) {
158 std::string shape_type;
160 shape_type = nav2::declare_or_get_parameter<std::string>(node, shape_name +
".type");
161 }
catch (
const std::exception & ex) {
163 get_logger(),
"Error while getting shape %s type: %s", shape_name.c_str(), ex.what());
167 if (shape_type ==
"polygon") {
168 auto polygon = std::make_shared<Polygon>(node);
169 if (!polygon->obtainParams(shape_name)) {
173 }
else if (shape_type ==
"circle") {
174 auto circle = std::make_shared<Circle>(node);
175 if (!circle->obtainParams(shape_name)) {
180 RCLCPP_ERROR(get_logger(),
181 "Please specify the correct type for shape %s. Supported types are 'polygon' and 'circle'",
190 std::vector<std::shared_ptr<Shape>>::iterator
194 if ((*it)->isUUID(uuid)) {
204 if (shape->getFrameID() !=
global_frame_id_ && !shape->getFrameID().empty()) {
208 get_logger(),
"Can not transform vector object from %s to %s frame",
219 double & min_x,
double & min_y,
double & max_x,
double & max_y)
const
221 min_x = std::numeric_limits<double>::max();
222 min_y = std::numeric_limits<double>::max();
223 max_x = std::numeric_limits<double>::lowest();
224 max_y = std::numeric_limits<double>::lowest();
226 double min_p_x, min_p_y, max_p_x, max_p_y;
228 shape->getBoundaries(min_p_x, min_p_y, max_p_x, max_p_y);
229 min_x = std::min(min_x, min_p_x);
230 min_y = std::min(min_y, min_p_y);
231 max_x = std::max(max_x, max_p_x);
232 max_y = std::max(max_y, max_p_y);
236 min_x == std::numeric_limits<double>::max() ||
237 min_y == std::numeric_limits<double>::max() ||
238 max_x == std::numeric_limits<double>::lowest() ||
239 max_y == std::numeric_limits<double>::lowest())
241 throw std::runtime_error(
"Can not obtain map boundaries");
246 const double & min_x,
const double & min_y,
const double & max_x,
const double & max_y)
249 int size_x =
static_cast<int>((max_x - min_x) /
resolution_) + 1;
250 int size_y =
static_cast<int>((max_y - min_y) /
resolution_) + 1;
253 throw std::runtime_error(
"Incorrect map x-size");
257 throw std::runtime_error(
"Incorrect map y-size");
261 map_ = std::make_shared<nav_msgs::msg::OccupancyGrid>();
265 map_->info.width !=
static_cast<unsigned int>(size_x) ||
266 map_->info.height !=
static_cast<unsigned int>(size_y))
270 map_->info.width = size_x;
271 map_->info.height = size_y;
272 }
else if (size_x > 0 && size_y > 0) {
279 map_->info.origin.position.x = min_x;
280 map_->info.origin.position.y = min_y;
287 if (shape->isFill()) {
289 double wx1 = std::numeric_limits<double>::max();
290 double wy1 = std::numeric_limits<double>::max();
291 double wx2 = std::numeric_limits<double>::lowest();
292 double wy2 = std::numeric_limits<double>::lowest();
293 unsigned int mx1 = 0;
294 unsigned int my1 = 0;
295 unsigned int mx2 = 0;
296 unsigned int my2 = 0;
298 shape->getBoundaries(wx1, wy1, wx2, wy2);
300 !nav2_util::worldToMap(
map_, wx1, wy1, mx1, my1) ||
301 !nav2_util::worldToMap(
map_, wx2, wy2, mx2, my2))
305 "Error to get shape boundaries on map (UUID: %s)", shape->getUUID().c_str());
310 for (
unsigned int my = my1; my <= my2; my++) {
311 for (
unsigned int mx = mx1; mx <= mx2; mx++) {
312 it = my *
map_->info.width + mx;
314 nav2_util::mapToWorld(
map_, mx, my, wx, wy);
315 if (shape->isPointInside(wx, wy)) {
330 auto map = std::make_unique<nav_msgs::msg::OccupancyGrid>(*
map_);
346 double min_x, min_y, max_x, max_y;
354 }
catch (
const std::exception & ex) {
355 RCLCPP_ERROR(get_logger(),
"Can not update map: %s", ex.what());
365 if (shape->getFrameID() !=
global_frame_id_ && !shape->getFrameID().empty()) {
371 RCLCPP_INFO(get_logger(),
"Publishing map dynamically at %f Hz rate",
update_frequency_);
380 RCLCPP_INFO(get_logger(),
"Publishing map once");
385 const std::shared_ptr<rmw_request_id_t>,
386 const std::shared_ptr<nav2_msgs::srv::AddShapes::Request> request,
387 std::shared_ptr<nav2_msgs::srv::AddShapes::Response> response)
391 response->success =
true;
396 for (
auto req_poly : request->polygons) {
397 nav2_msgs::msg::PolygonObject::SharedPtr new_params =
398 std::make_shared<nav2_msgs::msg::PolygonObject>(req_poly);
400 auto it =
findShape(new_params->uuid.uuid.data());
404 if ((*it)->getType() != POLYGON) {
407 "Shape (UUID: %s) is not a polygon type for a polygon update. Not adding shape.",
408 (*it)->getUUID().c_str());
409 response->success =
false;
414 std::shared_ptr<Polygon> polygon = std::static_pointer_cast<Polygon>(*it);
417 nav2_msgs::msg::PolygonObject::SharedPtr old_params = polygon->getParams();
418 if (!polygon->setParams(new_params)) {
421 "Failed to update existing polygon object (UUID: %s) with new params. "
422 "Reverting to old polygon params.",
423 (*it)->getUUID().c_str());
425 polygon->setParams(old_params);
427 response->success =
false;
431 std::shared_ptr<Polygon> polygon = std::make_shared<Polygon>(node);
432 if (polygon->setParams(new_params)) {
436 get_logger(),
"Failed to create a new polygon object using the provided params.");
437 response->success =
false;
443 for (
auto req_crcl : request->circles) {
444 nav2_msgs::msg::CircleObject::SharedPtr new_params =
445 std::make_shared<nav2_msgs::msg::CircleObject>(req_crcl);
447 auto it =
findShape(new_params->uuid.uuid.data());
451 if ((*it)->getType() != CIRCLE) {
454 "Shape (UUID: %s) is not a circle type for a circle update. Not adding shape.",
455 (*it)->getUUID().c_str());
456 response->success =
false;
461 std::shared_ptr<Circle> circle = std::static_pointer_cast<Circle>(*it);
464 nav2_msgs::msg::CircleObject::SharedPtr old_params = circle->getParams();
465 if (!circle->setParams(new_params)) {
468 "Failed to update existing circle object (UUID: %s) with new params. "
469 "Reverting to old circle params.",
470 (*it)->getUUID().c_str());
472 circle->setParams(old_params);
474 response->success =
false;
478 std::shared_ptr<Circle> circle = std::make_shared<Circle>(node);
479 if (circle->setParams(new_params)) {
483 get_logger(),
"Failed to create a new circle object using the provided params.");
484 response->success =
false;
493 const std::shared_ptr<rmw_request_id_t>,
494 const std::shared_ptr<nav2_msgs::srv::GetShapes::Request>,
495 std::shared_ptr<nav2_msgs::srv::GetShapes::Response> response)
497 std::shared_ptr<Polygon> polygon;
498 std::shared_ptr<Circle> circle;
501 switch (shape->getType()) {
503 polygon = std::static_pointer_cast<Polygon>(shape);
504 response->polygons.push_back(*(polygon->getParams()));
507 circle = std::static_pointer_cast<Circle>(shape);
508 response->circles.push_back(*(circle->getParams()));
511 RCLCPP_WARN(get_logger(),
"Unknown shape type (UUID: %s)", shape->getUUID().c_str());
517 const std::shared_ptr<rmw_request_id_t>,
518 const std::shared_ptr<nav2_msgs::srv::RemoveShapes::Request> request,
519 std::shared_ptr<nav2_msgs::srv::RemoveShapes::Response> response)
523 response->success =
true;
525 if (request->all_objects) {
530 for (
auto req_uuid : request->uuids) {
531 auto it =
findShape(req_uuid.uuid.data());
540 "Can not find shape to remove with UUID: %s",
541 unparseUUID(req_uuid.uuid.data()).c_str());
542 response->success =
false;
552 #include "rclcpp_components/register_node_macro.hpp"
void destroyBond()
Destroy bond connection to lifecycle manager.
nav2::LifecycleNode::SharedPtr shared_from_this()
Get a shared pointer of this.
void createBond()
Create bond connection to lifecycle manager.
A QoS profile for latched, reliable topics with a history of 1 messages.
Vector Object server node.
void addShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::AddShapes::Request > request, std::shared_ptr< nav2_msgs::srv::AddShapes::Response > response)
Callback for AddShapes service call. Reads all input vector objects from service request,...
void switchMapUpdate()
If map to be update dynamically, creates map processing timer, otherwise process map once.
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
TF listener.
void publishMap()
Publishes output map.
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
: Resets all services, publishers, map and TF-s
double process_map_
Whether to process and publish map.
nav2::ServiceServer< nav2_msgs::srv::GetShapes >::SharedPtr get_shapes_service_
GetShapes service.
bool transformVectorObjects()
Transform all vector shapes from their local frame to output map frame.
void processMap()
Calculates new map sizes, updates map, processes all vector objects on it and publishes output map on...
std::vector< std::shared_ptr< Shape > > shapes_
All shapes vector.
double update_frequency_
Frequency to dynamically update/publish the map (if necessary)
int8_t default_value_
Default value the output map to be filled with.
void removeShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::RemoveShapes::Request > request, std::shared_ptr< nav2_msgs::srv::RemoveShapes::Response > response)
Callback for RemoveShapes service call. Try to remove requested vector objects and switches map proce...
std::vector< std::shared_ptr< Shape > >::iterator findShape(const unsigned char *uuid)
Finds the shape with given UUID.
double resolution_
Output map resolution.
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
: Activates output map publisher and creates bond connection
nav2::Publisher< nav_msgs::msg::OccupancyGrid >::SharedPtr map_pub_
Output map publisher.
nav_msgs::msg::OccupancyGrid::SharedPtr map_
Output map with vector objects on it.
std::shared_ptr< tf2_ros::Buffer > tf_buffer_
TF buffer.
void putVectorObjectsOnMap()
Processes all vector objects on raster output map.
double transform_tolerance_
Transform tolerance.
std::string global_frame_id_
Frame of output map.
std::string map_topic_
@beirf Topic name where the output map to be published to
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called in shutdown state.
rclcpp::TimerBase::SharedPtr map_timer_
Map update timer.
void getMapBoundaries(double &min_x, double &min_y, double &max_x, double &max_y) const
Obtains map boundaries to place all vector objects inside.
void getShapesCallback(const std::shared_ptr< rmw_request_id_t > request_header, const std::shared_ptr< nav2_msgs::srv::GetShapes::Request > request, std::shared_ptr< nav2_msgs::srv::GetShapes::Response > response)
Callback for GetShapes service call. Gets all shapes and returns them to the service response.
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
: Deactivates map publisher and timer (if any), destroys bond connection
nav2::ServiceServer< nav2_msgs::srv::AddShapes >::SharedPtr add_shapes_service_
AddShapes service.
void updateMap(const double &min_x, const double &min_y, const double &max_x, const double &max_y)
Creates or updates existing map with required sizes and fills it with default value.
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
: Initializes TF buffer/listener, obtains ROS-parameters, creates incoming services,...
OverlayType overlay_type_
@Overlay Type of overlay of vector objects on the map
bool obtainParams()
Supporting routine obtaining all ROS-parameters.
nav2::ServiceServer< nav2_msgs::srv::RemoveShapes >::SharedPtr remove_shapes_service_
RemoveShapes service.