Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_map_server::VectorObjectServer Class Reference

Vector Object server node. More...

#include <nav2_map_server/include/nav2_map_server/vector_object_server.hpp>

Inheritance diagram for nav2_map_server::VectorObjectServer:
Inheritance graph
[legend]
Collaboration diagram for nav2_map_server::VectorObjectServer:
Collaboration graph
[legend]

Public Member Functions

 VectorObjectServer (const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 Constructor for the VectorObjectServer. More...
 
- Public Member Functions inherited from nav2::LifecycleNode
 LifecycleNode (const std::string &node_name, const std::string &ns, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor. More...
 
 LifecycleNode (const std::string &node_name, const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
 A lifecycle node constructor with no namespace. More...
 
template<typename ParamType >
ParamType declare_or_get_parameter (const std::string &parameter_name, const ParamType &default_value, const ParameterDescriptor &parameter_descriptor=ParameterDescriptor())
 Declares or gets a parameter. If the parameter is already declared, returns its value; otherwise declares it and returns the default value. More...
 
template<typename MessageT , typename CallbackT >
nav2::Subscription< MessageT >::SharedPtr create_subscription (const std::string &topic_name, CallbackT &&callback, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a subscription to a topic using Nav2 QoS profiles and SubscriptionOptions. More...
 
template<typename MessageT >
nav2::Publisher< MessageT >::SharedPtr create_publisher (const std::string &topic_name, const rclcpp::QoS &qos=nav2::qos::StandardTopicQoS(), const rclcpp::CallbackGroup::SharedPtr &callback_group=nullptr)
 Create a publisher to a topic using Nav2 QoS profiles and PublisherOptions. More...
 
template<typename ServiceT >
nav2::ServiceClient< ServiceT >::SharedPtr create_client (const std::string &service_name, bool use_internal_executor=false)
 Create a ServiceClient to interface with a service. More...
 
template<typename ServiceT >
nav2::ServiceServer< ServiceT >::SharedPtr create_service (const std::string &service_name, typename nav2::ServiceServer< ServiceT >::CallbackType cb, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ServiceServer to host with a service. More...
 
template<typename ActionT >
nav2::SimpleActionServer< ActionT >::SharedPtr create_action_server (const std::string &action_name, typename nav2::SimpleActionServer< ActionT >::ExecuteCallback execute_callback, typename nav2::SimpleActionServer< ActionT >::CompletionCallback compl_cb=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const bool realtime=false)
 Create a SimpleActionServer to host with an action. More...
 
template<typename ActionT >
nav2::ActionClient< ActionT >::SharedPtr create_action_client (const std::string &action_name, rclcpp::CallbackGroup::SharedPtr callback_group=nullptr)
 Create a ActionClient to call an action using. More...
 
nav2::LifecycleNode::SharedPtr shared_from_this ()
 Get a shared pointer of this.
 
nav2::LifecycleNode::WeakPtr weak_from_this ()
 Get a shared pointer of this.
 
nav2::CallbackReturn on_error (const rclcpp_lifecycle::State &)
 Abstracted on_error state transition callback, since unimplemented as of 2020 in the managed ROS2 node state machine. More...
 
void autostart ()
 Automatically configure and active the node.
 
virtual void on_rcl_preshutdown ()
 Perform preshutdown activities before our Context is shutdown. Note that this is related to our Context's shutdown sequence, not the lifecycle node state machine.
 
void createBond ()
 Create bond connection to lifecycle manager.
 
void destroyBond ()
 Destroy bond connection to lifecycle manager.
 

Protected Member Functions

nav2::CallbackReturn on_configure (const rclcpp_lifecycle::State &state) override
 : Initializes TF buffer/listener, obtains ROS-parameters, creates incoming services, and output map publisher More...
 
nav2::CallbackReturn on_activate (const rclcpp_lifecycle::State &state) override
 : Activates output map publisher and creates bond connection More...
 
nav2::CallbackReturn on_deactivate (const rclcpp_lifecycle::State &state) override
 : Deactivates map publisher and timer (if any), destroys bond connection More...
 
nav2::CallbackReturn on_cleanup (const rclcpp_lifecycle::State &state) override
 : Resets all services, publishers, map and TF-s More...
 
nav2::CallbackReturn on_shutdown (const rclcpp_lifecycle::State &state) override
 Called in shutdown state. More...
 
bool obtainParams ()
 Supporting routine obtaining all ROS-parameters. More...
 
std::vector< std::shared_ptr< Shape > >::iterator findShape (const unsigned char *uuid)
 Finds the shape with given UUID. More...
 
bool transformVectorObjects ()
 Transform all vector shapes from their local frame to output map frame. More...
 
void getMapBoundaries (double &min_x, double &min_y, double &max_x, double &max_y) const
 Obtains map boundaries to place all vector objects inside. More...
 
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. More...
 
void putVectorObjectsOnMap ()
 Processes all vector objects on raster output map.
 
void publishMap ()
 Publishes output map.
 
void processMap ()
 Calculates new map sizes, updates map, processes all vector objects on it and publishes output map one time.
 
void switchMapUpdate ()
 If map to be update dynamically, creates map processing timer, otherwise process map once.
 
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, creates them or updates their shape in case of existing objects and switches map processing/publishing routine. More...
 
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. More...
 
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 processing/publishing routine. More...
 
- Protected Member Functions inherited from nav2::LifecycleNode
void printLifecycleNodeNotification ()
 Print notifications for lifecycle node.
 
void register_rcl_preshutdown_callback ()
 
void runCleanups ()
 

Protected Attributes

std::shared_ptr< tf2_ros::Buffer > tf_buffer_
 TF buffer.
 
std::shared_ptr< tf2_ros::TransformListener > tf_listener_
 TF listener.
 
std::vector< std::shared_ptr< Shape > > shapes_
 All shapes vector.
 
double resolution_
 Output map resolution.
 
int8_t default_value_
 Default value the output map to be filled with.
 
OverlayType overlay_type_
 @Overlay Type of overlay of vector objects on the map
 
nav_msgs::msg::OccupancyGrid::SharedPtr map_
 Output map with vector objects on it.
 
double process_map_
 Whether to process and publish map.
 
std::string global_frame_id_
 Frame of output map.
 
double transform_tolerance_
 Transform tolerance.
 
double update_frequency_
 Frequency to dynamically update/publish the map (if necessary)
 
rclcpp::TimerBase::SharedPtr map_timer_
 Map update timer.
 
nav2::ServiceServer< nav2_msgs::srv::AddShapes >::SharedPtr add_shapes_service_
 AddShapes service.
 
nav2::ServiceServer< nav2_msgs::srv::GetShapes >::SharedPtr get_shapes_service_
 GetShapes service.
 
nav2::ServiceServer< nav2_msgs::srv::RemoveShapes >::SharedPtr remove_shapes_service_
 RemoveShapes service.
 
std::string map_topic_
 @beirf Topic name where the output map to be published to
 
nav2::Publisher< nav_msgs::msg::OccupancyGrid >::SharedPtr map_pub_
 Output map publisher.
 
- Protected Attributes inherited from nav2::LifecycleNode
std::unique_ptr< rclcpp::PreShutdownCallbackHandle > rcl_preshutdown_cb_handle_ {nullptr}
 
std::shared_ptr< bond::Bond > bond_ {nullptr}
 
double bond_heartbeat_period {0.1}
 
rclcpp::TimerBase::SharedPtr autostart_timer_
 

Additional Inherited Members

- Public Types inherited from nav2::LifecycleNode
using SharedPtr = std::shared_ptr< nav2::LifecycleNode >
 
using WeakPtr = std::weak_ptr< nav2::LifecycleNode >
 
using SharedConstPointer = std::shared_ptr< const nav2::LifecycleNode >
 

Detailed Description

Vector Object server node.

Definition at line 40 of file vector_object_server.hpp.

Constructor & Destructor Documentation

◆ VectorObjectServer()

nav2_map_server::VectorObjectServer::VectorObjectServer ( const rclcpp::NodeOptions &  options = rclcpp::NodeOptions())
explicit

Constructor for the VectorObjectServer.

Parameters
optionsAdditional options to control creation of the node.

Definition at line 36 of file vector_object_server.cpp.

Member Function Documentation

◆ addShapesCallback()

void nav2_map_server::VectorObjectServer::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 
)
protected

Callback for AddShapes service call. Reads all input vector objects from service request, creates them or updates their shape in case of existing objects and switches map processing/publishing routine.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 385 of file vector_object_server.cpp.

References findShape(), shapes_, nav2::LifecycleNode::shared_from_this(), and switchMapUpdate().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ findShape()

std::vector< std::shared_ptr< Shape > >::iterator nav2_map_server::VectorObjectServer::findShape ( const unsigned char *  uuid)
protected

Finds the shape with given UUID.

Parameters
uuidGiven UUID to search with
Returns
Iterator to the shape, if found. Otherwise past-the-end iterator.

Definition at line 192 of file vector_object_server.cpp.

References shapes_.

Referenced by addShapesCallback(), and removeShapesCallback().

Here is the caller graph for this function:

◆ getMapBoundaries()

void nav2_map_server::VectorObjectServer::getMapBoundaries ( double &  min_x,
double &  min_y,
double &  max_x,
double &  max_y 
) const
protected

Obtains map boundaries to place all vector objects inside.

Parameters
min_xoutput min X-boundary of required map
min_youtput min Y-boundary of required map
max_xoutput max X-boundary of required map
max_youtput max Y-boundary of required map
Exceptions
std::exceptionif can not obtain one of the map boundaries

Definition at line 219 of file vector_object_server.cpp.

References shapes_.

Referenced by processMap().

Here is the caller graph for this function:

◆ getShapesCallback()

void nav2_map_server::VectorObjectServer::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 
)
protected

Callback for GetShapes service call. Gets all shapes and returns them to the service response.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 493 of file vector_object_server.cpp.

References shapes_.

Referenced by on_configure().

Here is the caller graph for this function:

◆ obtainParams()

bool nav2_map_server::VectorObjectServer::obtainParams ( )
protected

Supporting routine obtaining all ROS-parameters.

Returns
True if all parameters were obtained or false in the failure case

Definition at line 140 of file vector_object_server.cpp.

References default_value_, global_frame_id_, map_topic_, overlay_type_, resolution_, and nav2::LifecycleNode::shared_from_this().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ on_activate()

nav2::CallbackReturn nav2_map_server::VectorObjectServer::on_activate ( const rclcpp_lifecycle::State &  state)
overrideprotected

: Activates output map publisher and creates bond connection

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 78 of file vector_object_server.cpp.

References nav2::LifecycleNode::createBond(), map_pub_, process_map_, and switchMapUpdate().

Here is the call graph for this function:

◆ on_cleanup()

nav2::CallbackReturn nav2_map_server::VectorObjectServer::on_cleanup ( const rclcpp_lifecycle::State &  state)
overrideprotected

: Resets all services, publishers, map and TF-s

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 114 of file vector_object_server.cpp.

References add_shapes_service_, get_shapes_service_, map_, map_pub_, remove_shapes_service_, shapes_, tf_buffer_, and tf_listener_.

◆ on_configure()

nav2::CallbackReturn nav2_map_server::VectorObjectServer::on_configure ( const rclcpp_lifecycle::State &  state)
overrideprotected

: Initializes TF buffer/listener, obtains ROS-parameters, creates incoming services, and output map publisher

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 41 of file vector_object_server.cpp.

References add_shapes_service_, addShapesCallback(), get_shapes_service_, getShapesCallback(), map_pub_, map_topic_, obtainParams(), remove_shapes_service_, removeShapesCallback(), tf_buffer_, and tf_listener_.

Here is the call graph for this function:

◆ on_deactivate()

nav2::CallbackReturn nav2_map_server::VectorObjectServer::on_deactivate ( const rclcpp_lifecycle::State &  state)
overrideprotected

: Deactivates map publisher and timer (if any), destroys bond connection

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 95 of file vector_object_server.cpp.

References nav2::LifecycleNode::destroyBond(), map_pub_, map_timer_, and process_map_.

Here is the call graph for this function:

◆ on_shutdown()

nav2::CallbackReturn nav2_map_server::VectorObjectServer::on_shutdown ( const rclcpp_lifecycle::State &  state)
overrideprotected

Called in shutdown state.

Parameters
stateLifecycle Node's state
Returns
Success or Failure

Definition at line 134 of file vector_object_server.cpp.

◆ removeShapesCallback()

void nav2_map_server::VectorObjectServer::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 
)
protected

Callback for RemoveShapes service call. Try to remove requested vector objects and switches map processing/publishing routine.

Parameters
request_headerService request header
requestService request
responseService response

Definition at line 517 of file vector_object_server.cpp.

References findShape(), shapes_, and switchMapUpdate().

Referenced by on_configure().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ transformVectorObjects()

bool nav2_map_server::VectorObjectServer::transformVectorObjects ( )
protected

Transform all vector shapes from their local frame to output map frame.

Returns
Whether all vector objects were transformed successfully

Definition at line 202 of file vector_object_server.cpp.

References global_frame_id_, shapes_, tf_buffer_, and transform_tolerance_.

Referenced by processMap().

Here is the caller graph for this function:

◆ updateMap()

void nav2_map_server::VectorObjectServer::updateMap ( const double &  min_x,
const double &  min_y,
const double &  max_x,
const double &  max_y 
)
protected

Creates or updates existing map with required sizes and fills it with default value.

Parameters
min_xmin X-boundary of new map
min_ymin Y-boundary of new map
max_xmax X-boundary of new map
max_ymax Y-boundary of new map
Exceptions
std::exceptionif map has negative X or Y size

Definition at line 246 of file vector_object_server.cpp.

References default_value_, global_frame_id_, map_, and resolution_.

Referenced by processMap().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: