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

#include <cb_yaw_rotate.hpp>

Inheritance diagram for cl_px4_mr::CbYawRotate:
Inheritance graph
Collaboration diagram for cl_px4_mr::CbYawRotate:
Collaboration graph

Public Member Functions

 CbYawRotate (float targetYawRad, bool relative=false)
 
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 targetYawRad_
 
bool relative_
 
float absoluteTargetYaw_ = 0.0f
 
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 26 of file cb_yaw_rotate.hpp.

Constructor & Destructor Documentation

◆ CbYawRotate()

cl_px4_mr::CbYawRotate::CbYawRotate ( float targetYawRad,
bool relative = false )

Definition at line 22 of file cb_yaw_rotate.cpp.

23: targetYawRad_(targetYawRad), relative_(relative)
24{
25}

Member Function Documentation

◆ onEntry()

void cl_px4_mr::CbYawRotate::onEntry ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 27 of file cb_yaw_rotate.cpp.

28{
31
32 float currentYaw = localPosition_->getHeading();
33
34 if (relative_)
35 {
36 absoluteTargetYaw_ = currentYaw + targetYawRad_;
37 }
38 else
39 {
41 }
42
43 // Normalize to [-PI, PI]
44 absoluteTargetYaw_ = std::atan2(std::sin(absoluteTargetYaw_), std::cos(absoluteTargetYaw_));
45
46 float curX = localPosition_->getX();
47 float curY = localPosition_->getY();
48 float curZ = localPosition_->getZ();
49
50 RCLCPP_INFO(
51 getLogger(), "CbYawRotate: rotating from %.2f to %.2f rad (relative=%d)", currentYaw,
53
55}
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 absoluteTargetYaw_, cl_px4_mr::CpVehicleLocalPosition::getHeading(), smacc2::ISmaccClientBehavior::getLogger(), cl_px4_mr::CpVehicleLocalPosition::getX(), cl_px4_mr::CpVehicleLocalPosition::getY(), cl_px4_mr::CpVehicleLocalPosition::getZ(), localPosition_, relative_, smacc2::ISmaccClientBehavior::requiresComponent(), cl_px4_mr::CpTrajectorySetpoint::setPositionNED(), targetYawRad_, and trajectorySetpoint_.

Here is the call graph for this function:

◆ onExit()

void cl_px4_mr::CbYawRotate::onExit ( )
overridevirtual

Reimplemented from smacc2::ISmaccClientBehavior.

Definition at line 57 of file cb_yaw_rotate.cpp.

57{}

◆ update()

void cl_px4_mr::CbYawRotate::update ( )
overridevirtual

Implements smacc2::ISmaccUpdatable.

Definition at line 59 of file cb_yaw_rotate.cpp.

60{
61 float currentYaw = localPosition_->getHeading();
62
63 // Compute shortest angular distance
64 float diff = absoluteTargetYaw_ - currentYaw;
65 diff = std::atan2(std::sin(diff), std::cos(diff));
66
67 if (std::abs(diff) < 0.1f)
68 {
69 RCLCPP_INFO(
70 getLogger(), "CbYawRotate: target yaw reached (error=%.3f rad) - posting success",
71 std::abs(diff));
72 this->postSuccessEvent();
73 }
74}

References absoluteTargetYaw_, cl_px4_mr::CpVehicleLocalPosition::getHeading(), smacc2::ISmaccClientBehavior::getLogger(), localPosition_, and smacc2::SmaccAsyncClientBehavior::postSuccessEvent().

Here is the call graph for this function:

Member Data Documentation

◆ absoluteTargetYaw_

float cl_px4_mr::CbYawRotate::absoluteTargetYaw_ = 0.0f
private

Definition at line 38 of file cb_yaw_rotate.hpp.

Referenced by onEntry(), and update().

◆ localPosition_

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

Definition at line 41 of file cb_yaw_rotate.hpp.

Referenced by onEntry(), and update().

◆ relative_

bool cl_px4_mr::CbYawRotate::relative_
private

Definition at line 37 of file cb_yaw_rotate.hpp.

Referenced by onEntry().

◆ targetYawRad_

float cl_px4_mr::CbYawRotate::targetYawRad_
private

Definition at line 36 of file cb_yaw_rotate.hpp.

Referenced by onEntry().

◆ trajectorySetpoint_

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

Definition at line 40 of file cb_yaw_rotate.hpp.

Referenced by onEntry().


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