15 #ifndef NAV2_ROUTE__PLUGINS__ROUTE_OPERATION_CLIENT_HPP_
16 #define NAV2_ROUTE__PLUGINS__ROUTE_OPERATION_CLIENT_HPP_
22 #include "rclcpp/rclcpp.hpp"
23 #include "rclcpp_lifecycle/lifecycle_node.hpp"
24 #include "nav2_route/interfaces/route_operation.hpp"
25 #include "nav2_core/route_exceptions.hpp"
26 #include "nav2_ros_common/node_utils.hpp"
27 #include "nav2_ros_common/service_client.hpp"
28 #include "std_srvs/srv/trigger.hpp"
33 using namespace std::chrono_literals;
61 template<
typename SrvT>
81 const nav2::LifecycleNode::SharedPtr ,
82 const std::string & ) {}
88 std::shared_ptr<typename SrvT::Request>,
const Metadata * ) {}
101 const nav2::LifecycleNode::SharedPtr node,
102 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
103 const std::string & name)
final
105 RCLCPP_INFO(node->get_logger(),
"Configuring route operation client: %s.", name.c_str());
107 logger_ = node->get_logger();
110 nav2::declare_parameter_if_not_declared(
111 node, getName() +
".service_name", rclcpp::ParameterValue(
""));
112 main_srv_name_ = node->get_parameter(getName() +
".service_name").as_string();
114 configureEvent(node, name);
119 if (!main_srv_name_.empty()) {
121 node->create_client<SrvT>(main_srv_name_,
true);
141 const geometry_msgs::msg::PoseStamped & ,
144 auto req = std::make_shared<typename SrvT::Request>();
145 std::shared_ptr<typename SrvT::Response> response;
146 populateRequest(req, mdata);
148 std::string srv_name;
149 srv_name = mdata->getValue<std::string>(
"service_name", srv_name);
150 if (srv_name.empty() && !main_client_) {
152 "Route operation service (" + getName() +
") needs 'server_name' "
153 "set in the param file or in the operation's metadata!");
157 if (srv_name.empty()) {
158 srv_name = main_srv_name_;
159 response = main_client_->invoke(req, std::chrono::nanoseconds(500ms));
161 auto node = node_.lock();
164 "Route operation service (" + getName() +
") failed to lock node.");
167 node->create_client<SrvT>(srv_name,
true);
168 response = client->invoke(req, std::chrono::nanoseconds(500ms));
170 }
catch (
const std::exception & e) {
172 "Route operation service (" + getName() +
") failed to call service: " +
173 srv_name +
" at Node " + std::to_string(node_achieved->nodeid));
178 "%s: Processed operation at Node %i with service %s.",
179 name_.c_str(), node_achieved->nodeid, srv_name.c_str());
180 return processResponse(response);
187 std::string
getName()
override {
return name_;}
194 RouteOperationType
processType() final {
return RouteOperationType::ON_GRAPH;}
196 std::string name_, main_srv_name_;
197 std::atomic_bool reroute_;
198 rclcpp::Logger logger_{rclcpp::get_logger(
"RouteOperationClient")};
199 typename nav2::ServiceClient<SrvT>::SharedPtr main_client_;
200 nav2::LifecycleNode::WeakPtr node_;
A route operation base class to trigger a service event at a node or edge. This is meant to be named ...
virtual OperationResult processResponse(std::shared_ptr< typename SrvT::Response >)
Process response from service to populate a result, if necessary.
void configure(const nav2::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber >, const std::string &name) final
Configure.
virtual void populateRequest(std::shared_ptr< typename SrvT::Request >, const Metadata *)
Populate request with details for service, if necessary.
RouteOperationType processType() final
Indication that the adjust speed limit route operation is performed on all state changes.
virtual void configureEvent(const nav2::LifecycleNode::SharedPtr, const std::string &)
Configure client with any necessary parameters, etc. May change or reset main_srv_name_ variable to c...
virtual ~RouteOperationClient()=default
destructor
RouteOperationClient()=default
Constructor.
std::string getName() override
Get name of the plugin for parameter scope mapping.
OperationResult perform(NodePtr node_achieved, EdgePtr, EdgePtr, const Route &, const geometry_msgs::msg::PoseStamped &, const Metadata *mdata) final
The main operation to call a service of arbitrary type and arbitrary name.
A plugin interface to perform an operation while tracking the route such as triggered from the graph ...
An object representing edges between nodes.
An object to store the nodes in the graph file.
a struct to hold return from an operation
An ordered set of nodes and edges corresponding to the planned route.