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_util/node_utils.hpp"
27 #include "std_srvs/srv/trigger.hpp"
32 using namespace std::chrono_literals;
60 template<
typename SrvT>
80 const rclcpp_lifecycle::LifecycleNode::SharedPtr ,
81 const std::string & ) {}
87 std::shared_ptr<typename SrvT::Request>,
const Metadata * ) {}
100 const rclcpp_lifecycle::LifecycleNode::SharedPtr node,
101 std::shared_ptr<nav2_costmap_2d::CostmapSubscriber>,
102 const std::string & name)
final
104 RCLCPP_INFO(node->get_logger(),
"Configuring route operation client: %s.", name.c_str());
106 logger_ = node->get_logger();
108 callback_group_ = node->create_callback_group(
109 rclcpp::CallbackGroupType::MutuallyExclusive,
111 callback_group_executor_.add_callback_group(callback_group_, node->get_node_base_interface());
113 nav2_util::declare_parameter_if_not_declared(
114 node, getName() +
".service_name", rclcpp::ParameterValue(
""));
115 main_srv_name_ = node->get_parameter(getName() +
".service_name").as_string();
117 configureEvent(node, name);
122 if (!main_srv_name_.empty()) {
123 main_client_ = node->create_client<SrvT>(
124 main_srv_name_, rclcpp::SystemDefaultsQoS(), callback_group_);
144 const geometry_msgs::msg::PoseStamped & ,
147 auto req = std::make_shared<typename SrvT::Request>();
148 std::shared_ptr<typename SrvT::Response> response;
149 populateRequest(req, mdata);
151 std::string srv_name;
152 srv_name = mdata->getValue<std::string>(
"service_name", srv_name);
153 if (srv_name.empty() && !main_client_) {
155 "Route operation service (" + getName() +
") needs 'server_name' "
156 "set in the param file or in the operation's metadata!");
159 if (srv_name.empty()) {
160 srv_name = main_srv_name_;
161 response = callService(main_client_, req);
163 auto node = node_.lock();
164 auto client = node->create_client<SrvT>(
165 srv_name, rclcpp::SystemDefaultsQoS(), callback_group_);
166 response = callService(client, req);
171 "%s: Processed operation at Node %i with service %s.",
172 name_.c_str(), node_achieved->nodeid, srv_name.c_str());
173 return processResponse(response);
176 std::shared_ptr<typename SrvT::Response> callService(
177 typename rclcpp::Client<SrvT>::SharedPtr client,
178 std::shared_ptr<typename SrvT::Request> req,
179 const std::chrono::nanoseconds timeout = std::chrono::nanoseconds(500ms))
181 auto node = node_.lock();
182 if (!client->wait_for_service(1s)) {
184 "Route operation service " +
185 std::string(client->get_service_name()) +
" is not available!");
188 auto result = client->async_send_request(req);
189 if (callback_group_executor_.spin_until_future_complete(result, timeout) !=
190 rclcpp::FutureReturnCode::SUCCESS)
193 "Route operation service " +
194 std::string(client->get_service_name()) +
" failed to call!");
204 std::string
getName()
override {
return name_;}
211 RouteOperationType
processType() final {
return RouteOperationType::ON_GRAPH;}
213 std::string name_, main_srv_name_;
214 std::atomic_bool reroute_;
215 rclcpp::Logger logger_{rclcpp::get_logger(
"RouteOperationClient")};
216 typename rclcpp::Client<SrvT>::SharedPtr main_client_;
217 rclcpp_lifecycle::LifecycleNode::WeakPtr node_;
218 rclcpp::CallbackGroup::SharedPtr callback_group_;
219 rclcpp::executors::SingleThreadedExecutor callback_group_executor_;
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.
virtual void populateRequest(std::shared_ptr< typename SrvT::Request >, const Metadata *)
Populate request with details for service, if necessary.
virtual void configureEvent(const rclcpp_lifecycle::LifecycleNode::SharedPtr, const std::string &)
Configure client with any necessary parameters, etc. May change or reset main_srv_name_ variable to c...
RouteOperationType processType() final
Indication that the adjust speed limit route operation is performed on all state changes.
virtual ~RouteOperationClient()=default
destructor
RouteOperationClient()=default
Constructor.
std::string getName() override
Get name of the plugin for parameter scope mapping.
void configure(const rclcpp_lifecycle::LifecycleNode::SharedPtr node, std::shared_ptr< nav2_costmap_2d::CostmapSubscriber >, const std::string &name) final
Configure.
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.