|
SMACC2
|
#include <cb_go_to_location.hpp>


Public Member Functions | |
| CbGoToLocation (float targetX, float targetY, float targetZ, float yaw=std::numeric_limits< float >::quiet_NaN()) | |
| void | onEntry () override |
| void | onExit () override |
Public Member Functions inherited from smacc2::SmaccAsyncClientBehavior | |
| template<typename TOrthogonal , typename TSourceObject > | |
| void | onStateOrthogonalAllocation () |
| virtual | ~SmaccAsyncClientBehavior () |
| template<typename TCallback , typename T > | |
| smacc2::SmaccSignalConnection | onSuccess (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| smacc2::SmaccSignalConnection | onFinished (TCallback callback, T *object) |
| template<typename TCallback , typename T > | |
| smacc2::SmaccSignalConnection | onFailure (TCallback callback, T *object) |
| void | requestForceFinish () |
| void | executeOnEntry () override |
| void | executeOnExit () override |
| void | waitOnEntryThread (bool requestFinish) |
| template<typename TCallbackMethod , typename T > | |
| smacc2::SmaccSignalConnection | onSuccess (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| smacc2::SmaccSignalConnection | onFinished (TCallbackMethod callback, T *object) |
| template<typename TCallbackMethod , typename T > | |
| smacc2::SmaccSignalConnection | onFailure (TCallbackMethod callback, T *object) |
Public Member Functions inherited from smacc2::ISmaccClientBehavior | |
| ISmaccClientBehavior () | |
| virtual | ~ISmaccClientBehavior () |
| ISmaccStateMachine * | getStateMachine () |
| std::string | getName () const |
| template<typename SmaccClientType > | |
| void | requiresClient (SmaccClientType *&storage) |
| template<typename SmaccComponentType > | |
| void | requiresComponent (SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT) |
Private Member Functions | |
| void | onGoalReachedCallback () |
Private Attributes | |
| float | targetX_ |
| float | targetY_ |
| float | targetZ_ |
| float | yaw_ |
| CpTrajectorySetpoint * | trajectorySetpoint_ = nullptr |
| CpGoalChecker * | goalChecker_ = nullptr |
Additional Inherited Members | |
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 26 of file cb_go_to_location.hpp.
| cl_px4_mr::CbGoToLocation::CbGoToLocation | ( | float | targetX, |
| float | targetY, | ||
| float | targetZ, | ||
| float | yaw = std::numeric_limits<float>::quiet_NaN() ) |
Definition at line 22 of file cb_go_to_location.cpp.
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 27 of file cb_go_to_location.cpp.
References smacc2::ISmaccStateMachine::createSignalConnection(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getStateMachine(), goalChecker_, cl_px4_mr::CpGoalChecker::onGoalReached_, onGoalReachedCallback(), smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpGoalChecker::setGoal(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), targetX_, targetY_, targetZ_, trajectorySetpoint_, and yaw_.

|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 43 of file cb_go_to_location.cpp.
References cl_px4_mr::CpGoalChecker::clearGoal(), and goalChecker_.

|
private |
Definition at line 45 of file cb_go_to_location.cpp.
References smacc2::ISmaccClientBehavior::getLogger(), and smacc2::SmaccAsyncClientBehavior::postSuccessEvent().
Referenced by onEntry().


|
private |
Definition at line 44 of file cb_go_to_location.hpp.
|
private |
Definition at line 39 of file cb_go_to_location.hpp.
Referenced by onEntry().
|
private |
Definition at line 40 of file cb_go_to_location.hpp.
Referenced by onEntry().
|
private |
Definition at line 41 of file cb_go_to_location.hpp.
Referenced by onEntry().
|
private |
Definition at line 43 of file cb_go_to_location.hpp.
Referenced by onEntry().
|
private |
Definition at line 42 of file cb_go_to_location.hpp.
Referenced by onEntry().