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

#include <cb_takeoff.hpp>

Inheritance diagram for cl_px4_mr::CbTakeOff:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbTakeOff:
Collaboration graph

Public Member Functions

 CbTakeOff (float targetAltitude=5.0f)
 
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_
 
CpVehicleCommandvehicleCommand_ = nullptr
 
CpOffboardKeepAliveoffboardKeepAlive_ = nullptr
 
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 28 of file cb_takeoff.hpp.

Constructor & Destructor Documentation

◆ CbTakeOff()

cl_px4_mr::CbTakeOff::CbTakeOff ( float targetAltitude = 5.0f)
explicit

Definition at line 28 of file cb_takeoff.cpp.

28: targetAltitude_(targetAltitude) {}

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbTakeOff::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 30 of file cb_takeoff.cpp.

31{
37
40
41 // 1. Enable offboard keepalive heartbeat
43
44 // 2. Hold current position to begin streaming setpoints
46
47 // 3. Wait for PX4 to see the setpoint stream (needs >2Hz for 1 second)
48 RCLCPP_INFO(getLogger(), "CbTakeOff: streaming setpoints before offboard switch...");
49 std::this_thread::sleep_for(std::chrono::seconds(2));
50
51 // 4. Switch to offboard mode
52 RCLCPP_INFO(getLogger(), "CbTakeOff: switching to offboard mode");
54
55 // 5. Small delay for mode switch to take effect
56 std::this_thread::sleep_for(std::chrono::milliseconds(500));
57
58 // 6. Command target altitude (NED: up is negative Z)
59 float currentX = localPosition_->getX();
60 float currentY = localPosition_->getY();
61 float targetZ = -targetAltitude_;
62 float currentHeading = localPosition_->getHeading();
63
64 RCLCPP_INFO(
65 getLogger(), "CbTakeOff: commanding altitude %.2f m (NED z=%.2f)", targetAltitude_, targetZ);
66 trajectorySetpoint_->setPositionNED(currentX, currentY, targetZ, currentHeading);
67
68 // 7. Set goal checker for target altitude
69 goalChecker_->setGoal(currentX, currentY, targetZ, 0.5f, 0.3f);
70}
CpVehicleLocalPosition * localPosition_
CpGoalChecker * goalChecker_
CpOffboardKeepAlive * offboardKeepAlive_
CpVehicleCommand * vehicleCommand_
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::CpOffboardKeepAlive::enable(), cl_px4_mr::CpVehicleLocalPosition::getHeading(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getStateMachine(), cl_px4_mr::CpVehicleLocalPosition::getX(), cl_px4_mr::CpVehicleLocalPosition::getY(), goalChecker_, cl_px4_mr::CpTrajectorySetpoint::hold(), localPosition_, offboardKeepAlive_, cl_px4_mr::CpGoalChecker::onGoalReached_, onGoalReachedCallback(), smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpGoalChecker::setGoal(), cl_px4_mr::CpVehicleCommand::setOffboardMode(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), targetAltitude_, trajectorySetpoint_, and vehicleCommand_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbTakeOff::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 72 of file cb_takeoff.cpp.

72{}

◆ onGoalReachedCallback()

void cl_px4_mr::CbTakeOff::onGoalReachedCallback ( )
private

Definition at line 74 of file cb_takeoff.cpp.

75{
76 RCLCPP_INFO(getLogger(), "CbTakeOff: target altitude reached - posting success");
77 this->postSuccessEvent();
78}

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

Definition at line 43 of file cb_takeoff.hpp.

Referenced by onEntry().

◆ localPosition_

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

Definition at line 44 of file cb_takeoff.hpp.

Referenced by onEntry().

◆ offboardKeepAlive_

CpOffboardKeepAlive* cl_px4_mr::CbTakeOff::offboardKeepAlive_ = nullptr
private

Definition at line 41 of file cb_takeoff.hpp.

Referenced by onEntry().

◆ targetAltitude_

float cl_px4_mr::CbTakeOff::targetAltitude_
private

Definition at line 39 of file cb_takeoff.hpp.

Referenced by onEntry().

◆ trajectorySetpoint_

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

Definition at line 42 of file cb_takeoff.hpp.

Referenced by onEntry().

◆ vehicleCommand_

CpVehicleCommand* cl_px4_mr::CbTakeOff::vehicleCommand_ = nullptr
private

Definition at line 40 of file cb_takeoff.hpp.

Referenced by onEntry().


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