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

#include <cb_arm_px4.hpp>

Inheritance diagram for cl_px4_mr::CbArmPX4:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbArmPX4:
Collaboration graph

Public Member Functions

 CbArmPX4 ()
 
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 onArmedCallback ()
 

Private Attributes

CpVehicleCommandvehicleCommand_ = nullptr
 
CpVehicleStatusvehicleStatus_ = nullptr
 
std::atomic< boolarmed_ {false}
 

Static Private Attributes

static constexpr int MAX_RETRIES = 5
 
static constexpr int RETRY_INTERVAL_SEC = 5
 

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_arm_px4.hpp.

Constructor & Destructor Documentation

◆ CbArmPX4()

cl_px4_mr::CbArmPX4::CbArmPX4 ( )

Definition at line 25 of file cb_arm_px4.cpp.

25{}

Member Function Documentation

◆ onArmedCallback()

void cl_px4_mr::CbArmPX4::onArmedCallback ( )
private

Definition at line 73 of file cb_arm_px4.cpp.

73{ armed_ = true; }
std::atomic< bool > armed_

References armed_.

Referenced by onEntry().

Here is the caller graph for this function:

◆ onEntry()

void cl_px4_mr::CbArmPX4::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 27 of file cb_arm_px4.cpp.

28{
31
34
35 for (int attempt = 0; attempt < MAX_RETRIES; attempt++)
36 {
37 if (attempt < 2)
38 {
39 RCLCPP_INFO(
40 getLogger(), "CbArmPX4: sending arm command (attempt %d/%d)", attempt + 1, MAX_RETRIES);
42 }
43 else
44 {
45 RCLCPP_WARN(getLogger(), "CbArmPX4: force-arming (attempt %d/%d)", attempt + 1, MAX_RETRIES);
47 }
48
49 // Wait for armed confirmation or timeout
50 for (int i = 0; i < RETRY_INTERVAL_SEC * 10; i++)
51 {
52 if (armed_) break;
53 std::this_thread::sleep_for(std::chrono::milliseconds(100));
54 }
55
56 if (armed_)
57 {
58 RCLCPP_INFO(getLogger(), "CbArmPX4: vehicle ARMED - posting success");
59 this->postSuccessEvent();
60 return;
61 }
62
63 RCLCPP_WARN(
64 getLogger(), "CbArmPX4: attempt %d/%d timed out, retrying...", attempt + 1, MAX_RETRIES);
65 }
66
67 RCLCPP_ERROR(getLogger(), "CbArmPX4: all %d attempts failed - posting failure", MAX_RETRIES);
68 this->postFailureEvent();
69}
CpVehicleStatus * vehicleStatus_
static constexpr int MAX_RETRIES
CpVehicleCommand * vehicleCommand_
static constexpr int RETRY_INTERVAL_SEC
smacc2::SmaccSignal< void()> onArmed_
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
smacc2::SmaccSignalConnection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)

References cl_px4_mr::CpVehicleCommand::arm(), armed_, smacc2::ISmaccStateMachine::createSignalConnection(), cl_px4_mr::CpVehicleCommand::forceArm(), smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getStateMachine(), MAX_RETRIES, cl_px4_mr::CpVehicleStatus::onArmed_, onArmedCallback(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), smacc2::ISmaccClientBehavior::requiresComponent(), RETRY_INTERVAL_SEC, vehicleCommand_, and vehicleStatus_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbArmPX4::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 71 of file cb_arm_px4.cpp.

71{}

Member Data Documentation

◆ armed_

std::atomic<bool> cl_px4_mr::CbArmPX4::armed_ {false}
private

Definition at line 39 of file cb_arm_px4.hpp.

39{false};

Referenced by onArmedCallback(), and onEntry().

◆ MAX_RETRIES

int cl_px4_mr::CbArmPX4::MAX_RETRIES = 5
staticconstexprprivate

Definition at line 40 of file cb_arm_px4.hpp.

Referenced by onEntry().

◆ RETRY_INTERVAL_SEC

int cl_px4_mr::CbArmPX4::RETRY_INTERVAL_SEC = 5
staticconstexprprivate

Definition at line 41 of file cb_arm_px4.hpp.

Referenced by onEntry().

◆ vehicleCommand_

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

Definition at line 37 of file cb_arm_px4.hpp.

Referenced by onEntry().

◆ vehicleStatus_

CpVehicleStatus* cl_px4_mr::CbArmPX4::vehicleStatus_ = nullptr
private

Definition at line 38 of file cb_arm_px4.hpp.

Referenced by onEntry().


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