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

#include <cb_change_altitude.hpp>

Inheritance diagram for cl_px4_mr::CbChangeAltitude:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbChangeAltitude:
Collaboration graph

Public Member Functions

 CbChangeAltitude (float targetAltitude)
 
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 targetAltitude_
 
CpTrajectorySetpointtrajectorySetpoint_ = nullptr
 
CpGoalCheckergoalChecker_ = nullptr
 
CpVehicleLocalPositionlocalPosition_ = 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_change_altitude.hpp.

Constructor & Destructor Documentation

◆ CbChangeAltitude()

cl_px4_mr::CbChangeAltitude::CbChangeAltitude ( float targetAltitude)
explicit

Definition at line 23 of file cb_change_altitude.cpp.

23: targetAltitude_(targetAltitude) {}

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbChangeAltitude::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 25 of file cb_change_altitude.cpp.

26{
30
33
34 float currentX = localPosition_->getX();
35 float currentY = localPosition_->getY();
36 float currentHeading = localPosition_->getHeading();
37 float targetZ = -targetAltitude_; // NED: up is negative Z
38
39 RCLCPP_INFO(
40 getLogger(), "CbChangeAltitude: changing altitude to %.2f m (NED z=%.2f)", targetAltitude_,
41 targetZ);
42
43 trajectorySetpoint_->setPositionNED(currentX, currentY, targetZ, currentHeading);
44 goalChecker_->setGoal(currentX, currentY, targetZ, 0.5f, 0.3f);
45}
CpVehicleLocalPosition * localPosition_
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(), cl_px4_mr::CpVehicleLocalPosition::getHeading(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getStateMachine(), cl_px4_mr::CpVehicleLocalPosition::getX(), cl_px4_mr::CpVehicleLocalPosition::getY(), goalChecker_, localPosition_, cl_px4_mr::CpGoalChecker::onGoalReached_, onGoalReachedCallback(), smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpGoalChecker::setGoal(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), targetAltitude_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbChangeAltitude::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 47 of file cb_change_altitude.cpp.

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

Here is the call graph for this function:

◆ onGoalReachedCallback()

void cl_px4_mr::CbChangeAltitude::onGoalReachedCallback ( )
private

Definition at line 49 of file cb_change_altitude.cpp.

50{
51 RCLCPP_INFO(getLogger(), "CbChangeAltitude: target altitude reached - posting success");
52 this->postSuccessEvent();
53}

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::CbChangeAltitude::goalChecker_ = nullptr
private

Definition at line 39 of file cb_change_altitude.hpp.

Referenced by onEntry(), and onExit().

◆ localPosition_

CpVehicleLocalPosition* cl_px4_mr::CbChangeAltitude::localPosition_ = nullptr
private

Definition at line 40 of file cb_change_altitude.hpp.

Referenced by onEntry().

◆ targetAltitude_

float cl_px4_mr::CbChangeAltitude::targetAltitude_
private

Definition at line 37 of file cb_change_altitude.hpp.

Referenced by onEntry().

◆ trajectorySetpoint_

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

Definition at line 38 of file cb_change_altitude.hpp.

Referenced by onEntry().


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