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

#include <cb_spiral_pattern.hpp>

Inheritance diagram for cl_px4_mr::CbSpiralPattern:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbSpiralPattern:
Collaboration graph

Public Member Functions

 CbSpiralPattern (float centerX, float centerY, float altitude, float maxRadius=20.0f, float spacing=3.0f, float speed=2.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 centerX_
 
float centerY_
 
float altitude_
 
float maxRadius_
 
float spacing_
 
float speed_
 
float theta_ = 0.0f
 
std::chrono::steady_clock::time_point lastUpdateTime_
 
CpTrajectorySetpointtrajectorySetpoint_ = 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
 
- Protected Member Functions inherited from smacc2::ISmaccUpdatable

Detailed Description

Definition at line 27 of file cb_spiral_pattern.hpp.

Constructor & Destructor Documentation

◆ CbSpiralPattern()

cl_px4_mr::CbSpiralPattern::CbSpiralPattern ( float centerX,
float centerY,
float altitude,
float maxRadius = 20.0f,
float spacing = 3.0f,
float speed = 2.0f )

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbSpiralPattern::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 33 of file cb_spiral_pattern.cpp.

34{
37
38 theta_ = 0.0f;
39 lastUpdateTime_ = std::chrono::steady_clock::now();
40
41 // Initial position is the spiral center
42 float z = -altitude_; // NED: up is negative
43
44 RCLCPP_INFO(
45 getLogger(),
46 "CbSpiralPattern: starting spiral center=[%.2f, %.2f] alt=%.2f maxR=%.2f spacing=%.2f "
47 "speed=%.2f",
49
51}
CpVehicleLocalPosition * localPosition_
CpTrajectorySetpoint * trajectorySetpoint_
std::chrono::steady_clock::time_point lastUpdateTime_
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_, localPosition_, maxRadius_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), spacing_, speed_, theta_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbSpiralPattern::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 53 of file cb_spiral_pattern.cpp.

53{}

◆ update()

void cl_px4_mr::CbSpiralPattern::update ( )
overridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 55 of file cb_spiral_pattern.cpp.

56{
57 auto now = std::chrono::steady_clock::now();
58 double dt = std::chrono::duration<double>(now - lastUpdateTime_).count();
59 lastUpdateTime_ = now;
60
61 // Archimedean spiral: r(theta) = a * theta
62 // where a = spacing / (2*PI) so each revolution adds 'spacing' meters of radius
63 float a = spacing_ / (2.0f * M_PI);
64
65 // Current radius
66 float r = a * theta_;
67
68 // Adaptive angular velocity to maintain constant linear speed
69 // Arc-length speed: ds/dt = sqrt(r^2 + a^2) * dtheta/dt
70 // Solving for dtheta/dt: omega = speed / sqrt(r^2 + a^2)
71 float omega = speed_ / std::sqrt(r * r + a * a);
72
73 // Advance angle
74 theta_ += omega * dt;
75
76 // Compute new position
77 float r_new = a * theta_;
78 float x = centerX_ + r_new * std::cos(theta_);
79 float y = centerY_ + r_new * std::sin(theta_);
80 float z = -altitude_; // NED
81
82 // Yaw: face direction of travel (derivatives of Archimedean spiral)
83 // dx/dtheta = a*cos(theta) - r*sin(theta)
84 // dy/dtheta = a*sin(theta) + r*cos(theta)
85 float dxdt = a * std::cos(theta_) - r_new * std::sin(theta_);
86 float dydt = a * std::sin(theta_) + r_new * std::cos(theta_);
87 float yaw = std::atan2(dydt, dxdt);
88
90
91 // Check completion
92 if (r_new >= maxRadius_)
93 {
94 RCLCPP_INFO(
95 getLogger(), "CbSpiralPattern: max radius %.2f reached (r=%.2f) - posting success",
96 maxRadius_, r_new);
97 this->postSuccessEvent();
98 }
99}

References altitude_, centerX_, centerY_, smacc2::ISmaccClientBehavior::getLogger(), lastUpdateTime_, maxRadius_, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), spacing_, speed_, theta_, and trajectorySetpoint_.

Here is the call graph for this function:

Member Data Documentation

◆ altitude_

float cl_px4_mr::CbSpiralPattern::altitude_
private

Definition at line 41 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ centerX_

float cl_px4_mr::CbSpiralPattern::centerX_
private

Definition at line 39 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ centerY_

float cl_px4_mr::CbSpiralPattern::centerY_
private

Definition at line 40 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ lastUpdateTime_

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

Definition at line 47 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ localPosition_

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

Definition at line 50 of file cb_spiral_pattern.hpp.

Referenced by onEntry().

◆ maxRadius_

float cl_px4_mr::CbSpiralPattern::maxRadius_
private

Definition at line 42 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ spacing_

float cl_px4_mr::CbSpiralPattern::spacing_
private

Definition at line 43 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ speed_

float cl_px4_mr::CbSpiralPattern::speed_
private

Definition at line 44 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ theta_

float cl_px4_mr::CbSpiralPattern::theta_ = 0.0f
private

Definition at line 46 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().

◆ trajectorySetpoint_

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

Definition at line 49 of file cb_spiral_pattern.hpp.

Referenced by onEntry(), and update().


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