15 #ifndef NAV2_MAP_SERVER__VECTOR_OBJECT_SERVER_HPP_
16 #define NAV2_MAP_SERVER__VECTOR_OBJECT_SERVER_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "nav_msgs/msg/occupancy_grid.hpp"
25 #include "tf2_ros/buffer.hpp"
26 #include "tf2_ros/transform_listener.hpp"
28 #include "nav2_msgs/srv/add_shapes.hpp"
29 #include "nav2_msgs/srv/remove_shapes.hpp"
30 #include "nav2_msgs/srv/get_shapes.hpp"
31 #include "nav2_ros_common/lifecycle_node.hpp"
33 #include "nav2_map_server/vector_object_utils.hpp"
34 #include "nav2_map_server/vector_object_shapes.hpp"
36 namespace nav2_map_server
47 explicit VectorObjectServer(
const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
56 nav2::CallbackReturn
on_configure(
const rclcpp_lifecycle::State & state)
override;
62 nav2::CallbackReturn
on_activate(
const rclcpp_lifecycle::State & state)
override;
68 nav2::CallbackReturn
on_deactivate(
const rclcpp_lifecycle::State & state)
override;
74 nav2::CallbackReturn
on_cleanup(
const rclcpp_lifecycle::State & state)
override;
80 nav2::CallbackReturn
on_shutdown(
const rclcpp_lifecycle::State & state)
override;
93 std::vector<std::shared_ptr<Shape>>::iterator
findShape(
const unsigned char * uuid);
109 void getMapBoundaries(
double & min_x,
double & min_y,
double & max_x,
double & max_y)
const;
120 const double & min_x,
const double & min_y,
const double & max_x,
const double & max_y);
154 const std::shared_ptr<rmw_request_id_t> request_header,
155 const std::shared_ptr<nav2_msgs::srv::AddShapes::Request> request,
156 std::shared_ptr<nav2_msgs::srv::AddShapes::Response> response);
166 const std::shared_ptr<rmw_request_id_t> request_header,
167 const std::shared_ptr<nav2_msgs::srv::GetShapes::Request> request,
168 std::shared_ptr<nav2_msgs::srv::GetShapes::Response> response);
178 const std::shared_ptr<rmw_request_id_t> request_header,
179 const std::shared_ptr<nav2_msgs::srv::RemoveShapes::Request> request,
180 std::shared_ptr<nav2_msgs::srv::RemoveShapes::Response> response);
199 nav_msgs::msg::OccupancyGrid::SharedPtr
map_;
223 nav2::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr
map_pub_;
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.
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.
VectorObjectServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the VectorObjectServer.
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.