SMACC2
Loading...
Searching...
No Matches
cp_waypoints_navigator.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
24#include <smacc2/smacc.hpp>
25
26#include <geometry_msgs/msg/pose.hpp>
28
29namespace cl_nav2z
30{
31class ClNav2Z;
32
33struct EvWaypointFinal : sc::event<EvWaypointFinal>
34{
35};
36
38{
39 std::optional<std::string> controllerName_;
40 std::optional<std::string> goalCheckerName_;
41};
42
43// This component contains a list of waypoints. These waypoints can
44// be iterated in the different states using CbNextWaiPoint
45// waypoint index is only incremented if the current waypoint is successfully reached
47{
48public:
50
52
53 void onInitialize() override;
54
55 template <typename TOrthogonal, typename TSourceObject>
57 {
58 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
59 }
60
61 std::optional<std::shared_future<
62 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > > >
64 std::optional<NavigateNextWaypointOptions> options = std::nullopt,
67
68 void stopWaitingResult();
69
73
74private:
76
77 void onGoalReached(const ClNav2Z::WrappedResult & res);
78 void onGoalCancelled(const ClNav2Z::WrappedResult & /*res*/);
79 void onGoalAborted(const ClNav2Z::WrappedResult & /*res*/);
80
81 boost::signals2::connection succeddedNav2ZClientConnection_;
82 boost::signals2::connection abortedNav2ZClientConnection_;
83 boost::signals2::connection cancelledNav2ZClientConnection_;
84};
85} // namespace cl_nav2z
boost::signals2::connection succeddedNav2ZClientConnection_
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt, cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr callback=cl_nav2z::ClNav2Z::SmaccNavigateResultSignal::WeakPtr())
boost::signals2::connection abortedNav2ZClientConnection_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
boost::signals2::connection cancelledNav2ZClientConnection_
void onGoalAborted(const ClNav2Z::WrappedResult &)
void onGoalCancelled(const ClNav2Z::WrappedResult &)
void onNavigationResult(const ClNav2Z::WrappedResult &r)
smacc2::SmaccSignal< void()> onNavigationRequestAborted
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
void onGoalReached(const ClNav2Z::WrappedResult &res)
std::weak_ptr< SmaccSignal< void(const WrappedResult &), optional_last_value< typename boost::function_traits< void(const WrappedResult &) >::result_type >, int, std::less< int >, function< void(const WrappedResult &) >, typename extended_signature< function_traits< void(const WrappedResult &) >::arity, void(const WrappedResult &) >::function_type, boost::signals2::mutex > > WeakPtr
namespace cl_nav2z class ClNav2Z
std::optional< std::string > goalCheckerName_