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

#include <cb_figure_eight.hpp>

Inheritance diagram for cl_px4_mr::CbFigureEight:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbFigureEight:
Collaboration graph

Public Member Functions

 CbFigureEight (float centerX, float centerY, float altitude, float size=5.0f, float speed=0.5f, int numLoops=1)
 
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 centerX_
 
float centerY_
 
float altitude_
 
float size_
 
float speed_
 
int numLoops_
 
float t_ = 0.0f
 
std::chrono::steady_clock::time_point lastUpdateTime_
 
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 26 of file cb_figure_eight.hpp.

Constructor & Destructor Documentation

◆ CbFigureEight()

cl_px4_mr::CbFigureEight::CbFigureEight ( float centerX,
float centerY,
float altitude,
float size = 5.0f,
float speed = 0.5f,
int numLoops = 1 )

Definition at line 21 of file cb_figure_eight.cpp.

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbFigureEight::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 32 of file cb_figure_eight.cpp.

33{
35
36 t_ = 0.0f;
37 lastUpdateTime_ = std::chrono::steady_clock::now();
38
39 // Command initial position (t=0: x=size, y=0 relative to center)
40 float x = centerX_ + size_;
41 float y = centerY_;
42 float z = -altitude_; // NED
43
44 RCLCPP_INFO(
45 getLogger(), "CbFigureEight: starting figure-8 center=[%.2f, %.2f] alt=%.2f size=%.2f loops=%d",
47
48 trajectorySetpoint_->setPositionNED(x, y, z, 0.0f);
49}
std::chrono::steady_clock::time_point lastUpdateTime_
CpTrajectorySetpoint * trajectorySetpoint_
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)

References altitude_, centerX_, centerY_, smacc2::ISmaccClientBehavior::getLogger(), lastUpdateTime_, numLoops_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), size_, t_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbFigureEight::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 51 of file cb_figure_eight.cpp.

51{}

◆ update()

void cl_px4_mr::CbFigureEight::update ( )
overridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 53 of file cb_figure_eight.cpp.

54{
55 auto now = std::chrono::steady_clock::now();
56 double dt = std::chrono::duration<double>(now - lastUpdateTime_).count();
57 lastUpdateTime_ = now;
58
59 t_ += speed_ * dt;
60
61 // Lemniscate of Bernoulli parametric equations
62 float sinT = std::sin(t_);
63 float cosT = std::cos(t_);
64 float denom = 1.0f + sinT * sinT;
65
66 float localX = size_ * cosT / denom;
67 float localY = size_ * sinT * cosT / denom;
68
69 float x = centerX_ + localX;
70 float y = centerY_ + localY;
71 float z = -altitude_; // NED
72
73 // Compute derivatives for yaw (face direction of travel)
74 float sinT2 = sinT * sinT;
75 float cosT2 = cosT * cosT;
76 float denom2 = denom * denom;
77 float dxdt = size_ * (-sinT * (1.0f + sinT2) - cosT * 2.0f * sinT * cosT) / denom2;
78 float dydt =
79 size_ * ((cosT2 - sinT2) * (1.0f + sinT2) - sinT * cosT * 2.0f * sinT * cosT) / denom2;
80 float yaw = std::atan2(dydt, dxdt);
81
83
84 // Check completion
85 float requiredT = numLoops_ * 2.0f * M_PI;
86 if (t_ >= requiredT)
87 {
88 RCLCPP_INFO(getLogger(), "CbFigureEight: %d loops completed - posting success", numLoops_);
89 this->postSuccessEvent();
90 }
91}

References altitude_, centerX_, centerY_, smacc2::ISmaccClientBehavior::getLogger(), lastUpdateTime_, numLoops_, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), size_, speed_, t_, and trajectorySetpoint_.

Here is the call graph for this function:

Member Data Documentation

◆ altitude_

float cl_px4_mr::CbFigureEight::altitude_
private

Definition at line 40 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ centerX_

float cl_px4_mr::CbFigureEight::centerX_
private

Definition at line 38 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ centerY_

float cl_px4_mr::CbFigureEight::centerY_
private

Definition at line 39 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ lastUpdateTime_

std::chrono::steady_clock::time_point cl_px4_mr::CbFigureEight::lastUpdateTime_
private

Definition at line 46 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ numLoops_

int cl_px4_mr::CbFigureEight::numLoops_
private

Definition at line 43 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ size_

float cl_px4_mr::CbFigureEight::size_
private

Definition at line 41 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ speed_

float cl_px4_mr::CbFigureEight::speed_
private

Definition at line 42 of file cb_figure_eight.hpp.

Referenced by update().

◆ t_

float cl_px4_mr::CbFigureEight::t_ = 0.0f
private

Definition at line 45 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().

◆ trajectorySetpoint_

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

Definition at line 48 of file cb_figure_eight.hpp.

Referenced by onEntry(), and update().


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