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

#include <cp_vehicle_local_position.hpp>

Inheritance diagram for cl_px4_mr::CpVehicleLocalPosition:
Inheritance graph
Collaboration diagram for cl_px4_mr::CpVehicleLocalPosition:
Collaboration graph

Public Member Functions

 CpVehicleLocalPosition ()
 
virtual ~CpVehicleLocalPosition ()
 
void onInitialize () override
 
float getX () const
 
float getY () const
 
float getZ () const
 
float getHeading () const
 
bool isValid () const
 
- Public Member Functions inherited from smacc2::ISmaccComponent
 ISmaccComponent ()
 
virtual ~ISmaccComponent ()
 
virtual std::string getName () const
 

Public Attributes

smacc2::SmaccSignal< void()> onPositionReceived_
 

Private Member Functions

void onPositionMessage (const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
 

Private Attributes

rclcpp::Subscription< px4_msgs::msg::VehicleLocalPosition >::SharedPtr subscriber_
 
float x_ = 0.0f
 
float y_ = 0.0f
 
float z_ = 0.0f
 
float heading_ = 0.0f
 
bool valid_ = false
 
std::mutex mutex_
 

Additional Inherited Members

- Protected Member Functions inherited from smacc2::ISmaccComponent
template<typename TOrthogonal , typename TClient >
void onComponentInitialization ()
 
template<typename EventType >
void postEvent (const EventType &ev)
 
template<typename EventType >
void postEvent ()
 
template<typename TOrthogonal , typename TSourceObject >
void onStateOrthogonalAllocation ()
 
template<typename TComponent >
void requiresComponent (TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TComponent >
void requiresComponent (std::string name, TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
 
template<typename TClient >
void requiresClient (TClient *&requiredClientStorage)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingComponent (TArgs... targs)
 
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs>
SmaccComponentType * createSiblingNamedComponent (std::string name, TArgs... targs)
 
rclcpp::Node::SharedPtr getNode ()
 
rclcpp::Logger getLogger () const
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 25 of file cp_vehicle_local_position.hpp.

Constructor & Destructor Documentation

◆ CpVehicleLocalPosition()

cl_px4_mr::CpVehicleLocalPosition::CpVehicleLocalPosition ( )

Definition at line 20 of file cp_vehicle_local_position.cpp.

20{}

◆ ~CpVehicleLocalPosition()

cl_px4_mr::CpVehicleLocalPosition::~CpVehicleLocalPosition ( )
virtual

Definition at line 22 of file cp_vehicle_local_position.cpp.

22{}

Member Function Documentation

◆ getHeading()

float cl_px4_mr::CpVehicleLocalPosition::getHeading ( ) const

Definition at line 64 of file cp_vehicle_local_position.cpp.

65{
66 std::lock_guard<std::mutex> lock(mutex_);
67 return heading_;
68}

References heading_, and mutex_.

Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CbTakeOff::onEntry().

Here is the caller graph for this function:

◆ getX()

float cl_px4_mr::CpVehicleLocalPosition::getX ( ) const

Definition at line 46 of file cp_vehicle_local_position.cpp.

47{
48 std::lock_guard<std::mutex> lock(mutex_);
49 return x_;
50}

References mutex_, and x_.

Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), cl_px4_mr::CbOrbitLocation::onEntry(), cl_px4_mr::CbTakeOff::onEntry(), and cl_px4_mr::CpGoalChecker::update().

Here is the caller graph for this function:

◆ getY()

float cl_px4_mr::CpVehicleLocalPosition::getY ( ) const

Definition at line 52 of file cp_vehicle_local_position.cpp.

53{
54 std::lock_guard<std::mutex> lock(mutex_);
55 return y_;
56}

References mutex_, and y_.

Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), cl_px4_mr::CbOrbitLocation::onEntry(), cl_px4_mr::CbTakeOff::onEntry(), and cl_px4_mr::CpGoalChecker::update().

Here is the caller graph for this function:

◆ getZ()

float cl_px4_mr::CpVehicleLocalPosition::getZ ( ) const

Definition at line 58 of file cp_vehicle_local_position.cpp.

59{
60 std::lock_guard<std::mutex> lock(mutex_);
61 return z_;
62}

References mutex_, and z_.

Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CpGoalChecker::update().

Here is the caller graph for this function:

◆ isValid()

bool cl_px4_mr::CpVehicleLocalPosition::isValid ( ) const

Definition at line 70 of file cp_vehicle_local_position.cpp.

71{
72 std::lock_guard<std::mutex> lock(mutex_);
73 return valid_;
74}

References mutex_, and valid_.

Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CpGoalChecker::update().

Here is the caller graph for this function:

◆ onInitialize()

void cl_px4_mr::CpVehicleLocalPosition::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 24 of file cp_vehicle_local_position.cpp.

25{
26 auto node = this->getNode();
27 subscriber_ = node->create_subscription<px4_msgs::msg::VehicleLocalPosition>(
28 "/fmu/out/vehicle_local_position", rclcpp::SensorDataQoS(),
29 std::bind(&CpVehicleLocalPosition::onPositionMessage, this, std::placeholders::_1));
30 RCLCPP_INFO(getLogger(), "CpVehicleLocalPosition: subscribed to /fmu/out/vehicle_local_position");
31}
void onPositionMessage(const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
rclcpp::Subscription< px4_msgs::msg::VehicleLocalPosition >::SharedPtr subscriber_
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), onPositionMessage(), and subscriber_.

Here is the call graph for this function:

◆ onPositionMessage()

void cl_px4_mr::CpVehicleLocalPosition::onPositionMessage ( const px4_msgs::msg::VehicleLocalPosition::SharedPtr msg)
private

Definition at line 33 of file cp_vehicle_local_position.cpp.

35{
36 std::lock_guard<std::mutex> lock(mutex_);
37 x_ = msg->x;
38 y_ = msg->y;
39 z_ = msg->z;
40 heading_ = msg->heading;
41 valid_ = msg->xy_valid && msg->z_valid;
42
44}
smacc2::SmaccSignal< void()> onPositionReceived_

References heading_, mutex_, onPositionReceived_, valid_, x_, y_, and z_.

Referenced by onInitialize().

Here is the caller graph for this function:

Member Data Documentation

◆ heading_

float cl_px4_mr::CpVehicleLocalPosition::heading_ = 0.0f
private

Definition at line 48 of file cp_vehicle_local_position.hpp.

Referenced by getHeading(), and onPositionMessage().

◆ mutex_

std::mutex cl_px4_mr::CpVehicleLocalPosition::mutex_
mutableprivate

Definition at line 50 of file cp_vehicle_local_position.hpp.

Referenced by getHeading(), getX(), getY(), getZ(), isValid(), and onPositionMessage().

◆ onPositionReceived_

smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleLocalPosition::onPositionReceived_

Definition at line 39 of file cp_vehicle_local_position.hpp.

Referenced by onPositionMessage().

◆ subscriber_

rclcpp::Subscription<px4_msgs::msg::VehicleLocalPosition>::SharedPtr cl_px4_mr::CpVehicleLocalPosition::subscriber_
private

Definition at line 44 of file cp_vehicle_local_position.hpp.

Referenced by onInitialize().

◆ valid_

bool cl_px4_mr::CpVehicleLocalPosition::valid_ = false
private

Definition at line 49 of file cp_vehicle_local_position.hpp.

Referenced by isValid(), and onPositionMessage().

◆ x_

float cl_px4_mr::CpVehicleLocalPosition::x_ = 0.0f
private

Definition at line 45 of file cp_vehicle_local_position.hpp.

Referenced by getX(), and onPositionMessage().

◆ y_

float cl_px4_mr::CpVehicleLocalPosition::y_ = 0.0f
private

Definition at line 46 of file cp_vehicle_local_position.hpp.

Referenced by getY(), and onPositionMessage().

◆ z_

float cl_px4_mr::CpVehicleLocalPosition::z_ = 0.0f
private

Definition at line 47 of file cp_vehicle_local_position.hpp.

Referenced by getZ(), and onPositionMessage().


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