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

#include <cb_hold_position.hpp>

Inheritance diagram for cl_px4_mr::CbHoldPosition:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbHoldPosition:
Collaboration graph

Public Member Functions

 CbHoldPosition (float durationSeconds=5.0f)
 
void onEntry () override
 
void onExit () override
 
void update () 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)
 
- Public Member Functions inherited from smacc2::ISmaccUpdatable
 ISmaccUpdatable ()
 
 ISmaccUpdatable (rclcpp::Duration duration)
 
void executeUpdate (rclcpp::Node::SharedPtr node)
 
void setUpdatePeriod (rclcpp::Duration duration)
 

Private Attributes

float durationSeconds_
 
std::chrono::steady_clock::time_point startTime_
 
CpTrajectorySetpointtrajectorySetpoint_ = 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
 
- Protected Member Functions inherited from smacc2::ISmaccUpdatable

Detailed Description

Definition at line 25 of file cb_hold_position.hpp.

Constructor & Destructor Documentation

◆ CbHoldPosition()

cl_px4_mr::CbHoldPosition::CbHoldPosition ( float durationSeconds = 5.0f)
explicit

Definition at line 21 of file cb_hold_position.cpp.

21: durationSeconds_(durationSeconds) {}

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbHoldPosition::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 23 of file cb_hold_position.cpp.

24{
26
27 RCLCPP_INFO(getLogger(), "CbHoldPosition: holding position for %.1f seconds", durationSeconds_);
28
30 startTime_ = std::chrono::steady_clock::now();
31}
CpTrajectorySetpoint * trajectorySetpoint_
std::chrono::steady_clock::time_point startTime_
virtual rclcpp::Logger getLogger() const
void requiresComponent(SmaccComponentType *&storage, ComponentRequirement requirementType=ComponentRequirement::SOFT)

References durationSeconds_, smacc2::ISmaccClientBehavior::getLogger(), cl_px4_mr::CpTrajectorySetpoint::hold(), smacc2::ISmaccClientBehavior::requiresComponent(), startTime_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbHoldPosition::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 33 of file cb_hold_position.cpp.

33{}

◆ update()

void cl_px4_mr::CbHoldPosition::update ( )
overridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 35 of file cb_hold_position.cpp.

36{
37 auto now = std::chrono::steady_clock::now();
38 double elapsed = std::chrono::duration<double>(now - startTime_).count();
39
40 if (elapsed >= durationSeconds_)
41 {
42 RCLCPP_INFO(
43 getLogger(), "CbHoldPosition: duration reached (%.1f s) - posting success", elapsed);
44 this->postSuccessEvent();
45 }
46}

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

Here is the call graph for this function:

Member Data Documentation

◆ durationSeconds_

float cl_px4_mr::CbHoldPosition::durationSeconds_
private

Definition at line 35 of file cb_hold_position.hpp.

Referenced by onEntry(), and update().

◆ startTime_

std::chrono::steady_clock::time_point cl_px4_mr::CbHoldPosition::startTime_
private

Definition at line 36 of file cb_hold_position.hpp.

Referenced by onEntry(), and update().

◆ trajectorySetpoint_

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

Definition at line 38 of file cb_hold_position.hpp.

Referenced by onEntry().


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