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

#include <cb_orbit_location.hpp>

Inheritance diagram for cl_px4_mr::CbOrbitLocation:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbOrbitLocation:
Collaboration graph

Public Member Functions

 CbOrbitLocation (float centerX, float centerY, float altitude, float radius=5.0f, float angularVelocity=0.5f, int numOrbits=3)
 
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 radius_
 
float angularVelocity_
 
int numOrbits_
 
float currentAngle_ = 0.0f
 
float startAngle_ = 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_orbit_location.hpp.

Constructor & Destructor Documentation

◆ CbOrbitLocation()

cl_px4_mr::CbOrbitLocation::CbOrbitLocation ( float centerX,
float centerY,
float altitude,
float radius = 5.0f,
float angularVelocity = 0.5f,
int numOrbits = 3 )

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbOrbitLocation::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 33 of file cb_orbit_location.cpp.

34{
37
38 // Compute starting angle from current position relative to center
39 float dx = localPosition_->getX() - centerX_;
40 float dy = localPosition_->getY() - centerY_;
41 startAngle_ = std::atan2(dy, dx);
43 lastUpdateTime_ = std::chrono::steady_clock::now();
44
45 // Command initial orbit position
46 float x = centerX_ + radius_ * std::cos(currentAngle_);
47 float y = centerY_ + radius_ * std::sin(currentAngle_);
48 float z = -altitude_; // NED: up is negative
49 float yaw = currentAngle_ + M_PI; // Face toward center
50
51 RCLCPP_INFO(
52 getLogger(), "CbOrbitLocation: starting orbit center=[%.2f, %.2f] r=%.2f alt=%.2f orbits=%d",
54
56}
std::chrono::steady_clock::time_point lastUpdateTime_
CpVehicleLocalPosition * localPosition_
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_, currentAngle_, smacc2::ISmaccClientBehavior::getLogger(), cl_px4_mr::CpVehicleLocalPosition::getX(), cl_px4_mr::CpVehicleLocalPosition::getY(), lastUpdateTime_, localPosition_, numOrbits_, radius_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), startAngle_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbOrbitLocation::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 58 of file cb_orbit_location.cpp.

58{}

◆ update()

void cl_px4_mr::CbOrbitLocation::update ( )
overridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 60 of file cb_orbit_location.cpp.

61{
62 auto now = std::chrono::steady_clock::now();
63 double dt = std::chrono::duration<double>(now - lastUpdateTime_).count();
64 lastUpdateTime_ = now;
65
66 // Advance angle
68
69 // Compute new position on circle
70 float x = centerX_ + radius_ * std::cos(currentAngle_);
71 float y = centerY_ + radius_ * std::sin(currentAngle_);
72 float z = -altitude_; // NED
73 float yaw = currentAngle_ + M_PI; // Face toward center
74
76
77 // Check if we've completed the required number of orbits
78 float totalAngle = currentAngle_ - startAngle_;
79 float requiredAngle = numOrbits_ * 2.0f * M_PI;
80
81 if (totalAngle >= requiredAngle)
82 {
83 RCLCPP_INFO(getLogger(), "CbOrbitLocation: %d orbits completed - posting success", numOrbits_);
84 this->postSuccessEvent();
85 }
86}

References altitude_, angularVelocity_, centerX_, centerY_, currentAngle_, smacc2::ISmaccClientBehavior::getLogger(), lastUpdateTime_, numOrbits_, smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), radius_, cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), startAngle_, and trajectorySetpoint_.

Here is the call graph for this function:

Member Data Documentation

◆ altitude_

float cl_px4_mr::CbOrbitLocation::altitude_
private

Definition at line 41 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ angularVelocity_

float cl_px4_mr::CbOrbitLocation::angularVelocity_
private

Definition at line 43 of file cb_orbit_location.hpp.

Referenced by update().

◆ centerX_

float cl_px4_mr::CbOrbitLocation::centerX_
private

Definition at line 39 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ centerY_

float cl_px4_mr::CbOrbitLocation::centerY_
private

Definition at line 40 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ currentAngle_

float cl_px4_mr::CbOrbitLocation::currentAngle_ = 0.0f
private

Definition at line 46 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ lastUpdateTime_

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

Definition at line 48 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ localPosition_

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

Definition at line 51 of file cb_orbit_location.hpp.

Referenced by onEntry().

◆ numOrbits_

int cl_px4_mr::CbOrbitLocation::numOrbits_
private

Definition at line 44 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ radius_

float cl_px4_mr::CbOrbitLocation::radius_
private

Definition at line 42 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ startAngle_

float cl_px4_mr::CbOrbitLocation::startAngle_ = 0.0f
private

Definition at line 47 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().

◆ trajectorySetpoint_

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

Definition at line 50 of file cb_orbit_location.hpp.

Referenced by onEntry(), and update().


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