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
22#include <cl_nav2z/cl_nav2z.hpp>
25#include <smacc2/smacc.hpp>
26
28#include <geometry_msgs/msg/pose.hpp>
29
30namespace cl_nav2z
31{
32class ClNav2Z;
33using namespace smacc2;
34
35struct EvWaypointFinal : sc::event<EvWaypointFinal>
36{
37};
38
40{
41 std::optional<std::string> controllerName_;
42 std::optional<std::string> goalCheckerName_;
43};
44
45// This component contains a list of waypoints. These waypoints can
46// be iterated in the different states using CbNextWaiPoint
47// waypoint index is only incremented if the current waypoint is successfully reached
49{
50public:
53
55
56 void onInitialize() override;
57
58 template <typename TOrthogonal, typename TSourceObject>
60 {
61 client_ = dynamic_cast<ClNav2Z *>(owner_);
62 waypointsEventDispatcher.initialize<TSourceObject, TOrthogonal>(client_);
63 this->requiresComponent(nav2ActionInterface_, ComponentRequirement::HARD);
64 }
65
66 std::optional<std::shared_future<
67 std::shared_ptr<rclcpp_action::ClientGoalHandle<nav2_msgs::action::NavigateToPose> > > >
68 sendNextGoal(std::optional<NavigateNextWaypointOptions> options = std::nullopt);
69
70 void stopWaitingResult();
71
75
76private:
78
82
83 boost::signals2::connection succeddedNav2ZClientConnection_;
84 boost::signals2::connection abortedNav2ZClientConnection_;
85 boost::signals2::connection cancelledNav2ZClientConnection_;
86};
87} // namespace cl_nav2z
void onGoalReached(const components::CpNav2ActionInterface::WrappedResult &res)
void onGoalAborted(const components::CpNav2ActionInterface::WrappedResult &)
boost::signals2::connection succeddedNav2ZClientConnection_
boost::signals2::connection abortedNav2ZClientConnection_
components::CpNav2ActionInterface * nav2ActionInterface_
smacc2::SmaccSignal< void()> onNavigationRequestCancelled
boost::signals2::connection cancelledNav2ZClientConnection_
void onNavigationResult(const components::CpNav2ActionInterface::WrappedResult &r)
void onGoalCancelled(const components::CpNav2ActionInterface::WrappedResult &)
std::optional< std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > > sendNextGoal(std::optional< NavigateNextWaypointOptions > options=std::nullopt)
smacc2::SmaccSignal< void()> onNavigationRequestAborted
smacc2::SmaccSignal< void()> onNavigationRequestSucceded
ISmaccClient * owner_
Definition component.hpp:88
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
namespace cl_nav2z class ClNav2Z
std::optional< std::string > goalCheckerName_