SMACC2
Loading...
Searching...
No Matches
Public Member Functions | Private Attributes | List of all members
cl_nitrosz::CbNavigateNextWaypointUntilReached Class Reference

#include <cb_navigate_next_waypoint_until_reached.hpp>

Inheritance diagram for cl_nitrosz::CbNavigateNextWaypointUntilReached:
Inheritance graph
Collaboration diagram for cl_nitrosz::CbNavigateNextWaypointUntilReached:
Collaboration graph

Public Member Functions

 CbNavigateNextWaypointUntilReached (std::string goalWaypointName, std::optional< NavigateNextWaypointOptions > options=std::nullopt)
 
virtual ~CbNavigateNextWaypointUntilReached ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
void onEntry () override
 
void onExit () override
 
void onNavigationActionSuccess (const ClNitrosZ::WrappedResult &r) override
 
- Public Member Functions inherited from cl_nitrosz::CbNavigateNextWaypoint
 CbNavigateNextWaypoint (std::optional< NavigateNextWaypointOptions > options=std::nullopt)
 
virtual ~CbNavigateNextWaypoint ()
 
- Public Member Functions inherited from cl_nitrosz::CbNav2ZClientBehaviorBase
virtual ~CbNav2ZClientBehaviorBase ()
 
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
- Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior
template<typename TOrthogonal , typename TSourceObject >
void onOrthogonalAllocation ()
 
virtual ~SmaccAsyncClientBehavior ()
 
template<typename TCallback , typename T >
boost::signals2::connection onSuccess (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFinished (TCallback callback, T *object)
 
template<typename TCallback , typename T >
boost::signals2::connection onFailure (TCallback callback, T *object)
 
void requestForceFinish ()
 
void executeOnEntry () override
 
void executeOnExit () override
 
void waitOnEntryThread (bool requestFinish)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onSuccess (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFinished (TCallbackMethod callback, T *object)
 
template<typename TCallbackMethod , typename T >
boost::signals2::connection onFailure (TCallbackMethod callback, T *object)
 
- Public Member Functions inherited from smacc2::ISmaccClientBehavior
 ISmaccClientBehavior ()
 
virtual ~ISmaccClientBehavior ()
 
ISmaccStateMachinegetStateMachine ()
 
std::string getName () const
 
template<typename SmaccClientType >
void requiresClient (SmaccClientType *&storage)
 
template<typename SmaccComponentType >
void requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false)
 

Private Attributes

std::string goalWaypointName_
 
std::function< void()> postEvGoalWaypointReached_
 

Additional Inherited Members

- Protected Member Functions inherited from cl_nitrosz::CbNav2ZClientBehaviorBase
void sendGoal (ClNitrosZ::Goal &goal)
 
void cancelGoal ()
 
bool isOwnActionResponse (const ClNitrosZ::WrappedResult &)
 
virtual void onNavigationResult (const ClNitrosZ::WrappedResult &)
 
virtual void onNavigationActionAbort (const ClNitrosZ::WrappedResult &)
 
- Protected Member Functions inherited from smacc2::SmaccAsyncClientBehavior
void postSuccessEvent ()
 
void postFailureEvent ()
 
virtual void dispose () override
 
bool isShutdownRequested ()
 onEntry is executed in a new thread. However the current state cannot be left until the onEntry thread finishes. This flag can be checked from the onEntry thread to force finishing the thread.
 
- Protected Member Functions inherited from smacc2::ISmaccClientBehavior
virtual void runtimeConfigure ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 
- Protected Attributes inherited from cl_nitrosz::CbNavigateNextWaypoint
CpWaypointNavigatorwaypointsNavigator_
 
NavigateNextWaypointOptions options_
 
cl_nitrosz::ClNitrosZ::SmaccNavigateResultSignal::SharedPtr navigationCallback_
 
- Protected Attributes inherited from cl_nitrosz::CbNav2ZClientBehaviorBase
cl_nitrosz::ClNitrosZnitroszClient_
 
cl_nitrosz::ClNitrosZ::SmaccNavigateResultSignal::SharedPtr navigationCallback_
 
rclcpp_action::ResultCode navigationResult_
 
std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > goalHandleFuture_
 

Detailed Description

Definition at line 31 of file cb_navigate_next_waypoint_until_reached.hpp.

Constructor & Destructor Documentation

◆ CbNavigateNextWaypointUntilReached()

cl_nitrosz::CbNavigateNextWaypointUntilReached::CbNavigateNextWaypointUntilReached ( std::string  goalWaypointName,
std::optional< NavigateNextWaypointOptions options = std::nullopt 
)

Definition at line 25 of file cb_navigate_next_waypoint_until_reached.cpp.

27: CbNavigateNextWaypoint(options), goalWaypointName_(goalWaypointName)
28{
29}
CbNavigateNextWaypoint(std::optional< NavigateNextWaypointOptions > options=std::nullopt)

◆ ~CbNavigateNextWaypointUntilReached()

cl_nitrosz::CbNavigateNextWaypointUntilReached::~CbNavigateNextWaypointUntilReached ( )
virtual

Definition at line 31 of file cb_navigate_next_waypoint_until_reached.cpp.

31{}

Member Function Documentation

◆ onEntry()

void cl_nitrosz::CbNavigateNextWaypointUntilReached::onEntry ( )
overridevirtual

◆ onExit()

void cl_nitrosz::CbNavigateNextWaypointUntilReached::onExit ( )
overridevirtual

◆ onNavigationActionSuccess()

void cl_nitrosz::CbNavigateNextWaypointUntilReached::onNavigationActionSuccess ( const ClNitrosZ::WrappedResult r)
inlineoverridevirtual

Reimplemented from cl_nitrosz::CbNav2ZClientBehaviorBase.

Definition at line 58 of file cb_navigate_next_waypoint_until_reached.hpp.

59 {
60 // if (!isOwnActionResponse(r))
61 // {
62 // RCLCPP_WARN(
63 // getLogger(), "[%s] Propagating success event skipped. Action response is not ours.",
64 // getName().c_str());
65 // return;
66 // }
67
68 navigationResult_ = r.code;
69
70 RCLCPP_INFO(
71 getLogger(), "[%s] Propagating success event from action server", getName().c_str());
72
73 waypointsNavigator_ = nitroszClient_->getComponent<CpWaypointNavigator>();
74
75 auto current_waypoint_name = waypointsNavigator_->getCurrentWaypointName();
76
77 if (current_waypoint_name == this->goalWaypointName_)
78 {
79 RCLCPP_INFO(
80 getLogger(),
81 "[CbNavigateNextWaypointUntilReached] GoalReached current iteration waypoint i: %ld with "
82 "name '%s'",
83 waypointsNavigator_->getCurrentWaypointIndex(), current_waypoint_name->c_str());
84
86 }
87 else
88 {
89 RCLCPP_INFO(
90 getLogger(),
91 "[CbNavigateNextWaypointUntilReached] goal:'%s' current:'%s'. keep navigating.",
92 goalWaypointName_.c_str(), current_waypoint_name->c_str());
93 }
94
95 this->postSuccessEvent();
96 }
std::optional< std::string > getCurrentWaypointName() const
virtual rclcpp::Logger getLogger() const

References smacc2::ISmaccClient::getComponent(), cl_nitrosz::CpWaypointNavigatorBase::getCurrentWaypointIndex(), cl_nitrosz::CpWaypointNavigatorBase::getCurrentWaypointName(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getName(), goalWaypointName_, cl_nitrosz::CbNav2ZClientBehaviorBase::navigationResult_, cl_nitrosz::CbNav2ZClientBehaviorBase::nitroszClient_, postEvGoalWaypointReached_, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), and cl_nitrosz::CbNavigateNextWaypoint::waypointsNavigator_.

Here is the call graph for this function:

◆ onOrthogonalAllocation()

template<typename TOrthogonal , typename TSourceObject >
void cl_nitrosz::CbNavigateNextWaypointUntilReached::onOrthogonalAllocation ( )
inline

Definition at line 41 of file cb_navigate_next_waypoint_until_reached.hpp.

42 {
44 CbNavigateNextWaypoint::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
45
47 {
48 this->postEvent<EvGoalWaypointReached<TSourceObject, TOrthogonal>>();
49
50 // nitroszClient_->onSucceeded(&CbNavigateNextWaypointUntilReached::onWaypointReached, this);
51 };
52 }
void requiresClient(SmaccClientType *&storage)

References cl_nitrosz::CbNav2ZClientBehaviorBase::nitroszClient_, postEvGoalWaypointReached_, and smacc2::ISmaccClientBehavior::requiresClient().

Here is the call graph for this function:

Member Data Documentation

◆ goalWaypointName_

std::string cl_nitrosz::CbNavigateNextWaypointUntilReached::goalWaypointName_
private

◆ postEvGoalWaypointReached_

std::function<void()> cl_nitrosz::CbNavigateNextWaypointUntilReached::postEvGoalWaypointReached_
private

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