SMACC2
Loading...
Searching...
No Matches
cl_px4_mr::CbGoToLocation Class Reference

#include <cb_go_to_location.hpp>

Inheritance diagram for cl_px4_mr::CbGoToLocation:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbGoToLocation:
Collaboration graph

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 ()
 
ISmaccStateMachinegetStateMachine ()
 
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_
 
CpTrajectorySetpointtrajectorySetpoint_ = nullptr
 
CpGoalCheckergoalChecker_ = 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 ()
 
ISmaccStategetCurrentState ()
 
virtual rclcpp::Node::SharedPtr getNode () const
 
virtual rclcpp::Logger getLogger () const
 

Detailed Description

Definition at line 26 of file cb_go_to_location.hpp.

Constructor & Destructor Documentation

◆ CbGoToLocation()

cl_px4_mr::CbGoToLocation::CbGoToLocation ( float targetX,
float targetY,
float targetZ,
float yaw = std::numeric_limits<float>::quiet_NaN() )

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbGoToLocation::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 27 of file cb_go_to_location.cpp.

28{
31
34
35 RCLCPP_INFO(
36 getLogger(), "CbGoToLocation: navigating to [%.2f, %.2f, %.2f] yaw=%.2f", targetX_, targetY_,
37 targetZ_, yaw_);
38
41}
CpTrajectorySetpoint * trajectorySetpoint_
void setGoal(float x, float y, float z, float xy_tolerance=0.5f, float z_tolerance=0.3f)
smacc2::SmaccSignal< void()> onGoalReached_
void setPositionNED(float x, float y, float z, float yaw=std::numeric_limits< float >::quiet_NaN())
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
smacc2::SmaccSignalConnection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

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_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbGoToLocation::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 43 of file cb_go_to_location.cpp.

References cl_px4_mr::CpGoalChecker::clearGoal(), and goalChecker_.

Here is the call graph for this function:

◆ onGoalReachedCallback()

void cl_px4_mr::CbGoToLocation::onGoalReachedCallback ( )
private

Definition at line 45 of file cb_go_to_location.cpp.

46{
47 RCLCPP_INFO(getLogger(), "CbGoToLocation: goal reached - posting success");
48 this->postSuccessEvent();
49}

References smacc2::ISmaccClientBehavior::getLogger(), and smacc2::SmaccAsyncClientBehavior::postSuccessEvent().

Referenced by onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ goalChecker_

CpGoalChecker* cl_px4_mr::CbGoToLocation::goalChecker_ = nullptr
private

Definition at line 44 of file cb_go_to_location.hpp.

Referenced by onEntry(), and onExit().

◆ targetX_

float cl_px4_mr::CbGoToLocation::targetX_
private

Definition at line 39 of file cb_go_to_location.hpp.

Referenced by onEntry().

◆ targetY_

float cl_px4_mr::CbGoToLocation::targetY_
private

Definition at line 40 of file cb_go_to_location.hpp.

Referenced by onEntry().

◆ targetZ_

float cl_px4_mr::CbGoToLocation::targetZ_
private

Definition at line 41 of file cb_go_to_location.hpp.

Referenced by onEntry().

◆ trajectorySetpoint_

CpTrajectorySetpoint* cl_px4_mr::CbGoToLocation::trajectorySetpoint_ = nullptr
private

Definition at line 43 of file cb_go_to_location.hpp.

Referenced by onEntry().

◆ yaw_

float cl_px4_mr::CbGoToLocation::yaw_
private

Definition at line 42 of file cb_go_to_location.hpp.

Referenced by onEntry().


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