|
SMACC2
|
#include <cp_vehicle_local_position.hpp>


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 |
| ISmaccStateMachine * | getStateMachine () |
Protected Attributes inherited from smacc2::ISmaccComponent | |
| ISmaccStateMachine * | stateMachine_ |
| ISmaccClient * | owner_ |
Definition at line 25 of file cp_vehicle_local_position.hpp.
| cl_px4_mr::CpVehicleLocalPosition::CpVehicleLocalPosition | ( | ) |
Definition at line 20 of file cp_vehicle_local_position.cpp.
|
virtual |
Definition at line 22 of file cp_vehicle_local_position.cpp.
| float cl_px4_mr::CpVehicleLocalPosition::getHeading | ( | ) | const |
Definition at line 64 of file cp_vehicle_local_position.cpp.
References heading_, and mutex_.
Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CbTakeOff::onEntry().

| float cl_px4_mr::CpVehicleLocalPosition::getX | ( | ) | const |
Definition at line 46 of file cp_vehicle_local_position.cpp.
Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), cl_px4_mr::CbOrbitLocation::onEntry(), cl_px4_mr::CbTakeOff::onEntry(), and cl_px4_mr::CpGoalChecker::update().

| float cl_px4_mr::CpVehicleLocalPosition::getY | ( | ) | const |
Definition at line 52 of file cp_vehicle_local_position.cpp.
Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), cl_px4_mr::CbOrbitLocation::onEntry(), cl_px4_mr::CbTakeOff::onEntry(), and cl_px4_mr::CpGoalChecker::update().

| float cl_px4_mr::CpVehicleLocalPosition::getZ | ( | ) | const |
Definition at line 58 of file cp_vehicle_local_position.cpp.
Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CpGoalChecker::update().

| bool cl_px4_mr::CpVehicleLocalPosition::isValid | ( | ) | const |
Definition at line 70 of file cp_vehicle_local_position.cpp.
References mutex_, and valid_.
Referenced by cl_px4_mr::CpTrajectorySetpoint::hold(), and cl_px4_mr::CpGoalChecker::update().

|
overridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 24 of file cp_vehicle_local_position.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), onPositionMessage(), and subscriber_.

|
private |
Definition at line 33 of file cp_vehicle_local_position.cpp.
References heading_, mutex_, onPositionReceived_, valid_, x_, y_, and z_.
Referenced by onInitialize().

|
private |
Definition at line 48 of file cp_vehicle_local_position.hpp.
Referenced by getHeading(), and onPositionMessage().
|
mutableprivate |
Definition at line 50 of file cp_vehicle_local_position.hpp.
Referenced by getHeading(), getX(), getY(), getZ(), isValid(), and onPositionMessage().
| smacc2::SmaccSignal<void()> cl_px4_mr::CpVehicleLocalPosition::onPositionReceived_ |
Definition at line 39 of file cp_vehicle_local_position.hpp.
Referenced by onPositionMessage().
|
private |
Definition at line 44 of file cp_vehicle_local_position.hpp.
Referenced by onInitialize().
|
private |
Definition at line 49 of file cp_vehicle_local_position.hpp.
Referenced by isValid(), and onPositionMessage().
|
private |
Definition at line 45 of file cp_vehicle_local_position.hpp.
Referenced by getX(), and onPositionMessage().
|
private |
Definition at line 46 of file cp_vehicle_local_position.hpp.
Referenced by getY(), and onPositionMessage().
|
private |
Definition at line 47 of file cp_vehicle_local_position.hpp.
Referenced by getZ(), and onPositionMessage().