SMACC2
|
#include <cb_navigate_next_waypoint.hpp>
Protected Attributes | |
CpWaypointNavigator * | waypointsNavigator_ |
NavigateNextWaypointOptions | options_ |
cl_nitrosz::ClNitrosZ::SmaccNavigateResultSignal::SharedPtr | navigationCallback_ |
Protected Attributes inherited from cl_nitrosz::CbNav2ZClientBehaviorBase | |
cl_nitrosz::ClNitrosZ * | nitroszClient_ |
cl_nitrosz::ClNitrosZ::SmaccNavigateResultSignal::SharedPtr | navigationCallback_ |
rclcpp_action::ResultCode | navigationResult_ |
std::shared_future< std::shared_ptr< rclcpp_action::ClientGoalHandle< nav2_msgs::action::NavigateToPose > > > | goalHandleFuture_ |
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 | onNavigationActionSuccess (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 () |
ISmaccState * | getCurrentState () |
virtual rclcpp::Node::SharedPtr | getNode () const |
virtual rclcpp::Logger | getLogger () const |
Definition at line 29 of file cb_navigate_next_waypoint.hpp.
cl_nitrosz::CbNavigateNextWaypoint::CbNavigateNextWaypoint | ( | std::optional< NavigateNextWaypointOptions > | options = std::nullopt | ) |
Definition at line 25 of file cb_navigate_next_waypoint.cpp.
References options_.
|
virtual |
Definition at line 30 of file cb_navigate_next_waypoint.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nitrosz::CbNavigateNextWaypointUntilReached.
Definition at line 32 of file cb_navigate_next_waypoint.cpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), smacc2::ISmaccClient::getComponent(), cl_nitrosz::CpWaypointNavigatorBase::getCurrentWaypointIndex(), cl_nitrosz::CpWaypointNavigatorBase::getCurrentWaypointName(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getStateMachine(), navigationCallback_, cl_nitrosz::CbNav2ZClientBehaviorBase::nitroszClient_, cl_nitrosz::CbNav2ZClientBehaviorBase::onNavigationResult(), options_, cl_nitrosz::CpWaypointNavigator::sendNextGoal(), and waypointsNavigator_.
Referenced by cl_nitrosz::CbNavigateNamedWaypoint::onEntry(), and cl_nitrosz::CbNavigateNextWaypointUntilReached::onEntry().
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Reimplemented in cl_nitrosz::CbNavigateNextWaypointUntilReached.
Definition at line 59 of file cb_navigate_next_waypoint.cpp.
References cl_nitrosz::CpWaypointNavigator::stopWaitingResult(), and waypointsNavigator_.
Referenced by cl_nitrosz::CbNavigateNamedWaypoint::onExit(), and cl_nitrosz::CbNavigateNextWaypointUntilReached::onExit().
|
protected |
Definition at line 45 of file cb_navigate_next_waypoint.hpp.
Referenced by onEntry().
|
protected |
Definition at line 43 of file cb_navigate_next_waypoint.hpp.
Referenced by CbNavigateNextWaypoint(), and onEntry().
|
protected |
Definition at line 41 of file cb_navigate_next_waypoint.hpp.
Referenced by onEntry(), onExit(), and cl_nitrosz::CbNavigateNextWaypointUntilReached::onNavigationActionSuccess().