|
SMACC2
|
#include <cp_vehicle_command.hpp>


Public Member Functions | |
| CpVehicleCommand () | |
| virtual | ~CpVehicleCommand () |
| void | onInitialize () override |
| void | sendCommand (uint32_t command, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, double param5=0.0, double param6=0.0, float param7=0.0f) |
| void | arm () |
| void | forceArm () |
| void | disarm () |
| void | setOffboardMode () |
| void | land () |
| void | takeoff (float altitude) |
Public Member Functions inherited from smacc2::ISmaccComponent | |
| ISmaccComponent () | |
| virtual | ~ISmaccComponent () |
| virtual std::string | getName () const |
Private Attributes | |
| rclcpp::Publisher< px4_msgs::msg::VehicleCommand >::SharedPtr | publisher_ |
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 24 of file cp_vehicle_command.hpp.
| cl_px4_mr::CpVehicleCommand::CpVehicleCommand | ( | ) |
Definition at line 20 of file cp_vehicle_command.cpp.
|
virtual |
Definition at line 22 of file cp_vehicle_command.cpp.
| void cl_px4_mr::CpVehicleCommand::arm | ( | ) |
Definition at line 58 of file cp_vehicle_command.cpp.
References sendCommand().
Referenced by cl_px4_mr::CbArmPX4::onEntry().


| void cl_px4_mr::CpVehicleCommand::disarm | ( | ) |
Definition at line 69 of file cp_vehicle_command.cpp.
References sendCommand().
Referenced by cl_px4_mr::CbDisarmPX4::onEntry().


| void cl_px4_mr::CpVehicleCommand::forceArm | ( | ) |
Definition at line 63 of file cp_vehicle_command.cpp.
References sendCommand().
Referenced by cl_px4_mr::CbArmPX4::onEntry().


| void cl_px4_mr::CpVehicleCommand::land | ( | ) |
Definition at line 79 of file cp_vehicle_command.cpp.
References sendCommand().
Referenced by cl_px4_mr::CbLand::onEntry().


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

| void cl_px4_mr::CpVehicleCommand::sendCommand | ( | uint32_t | command, |
| float | param1 = 0.0f, | ||
| float | param2 = 0.0f, | ||
| float | param3 = 0.0f, | ||
| float | param4 = 0.0f, | ||
| double | param5 = 0.0, | ||
| double | param6 = 0.0, | ||
| float | param7 = 0.0f ) |
Definition at line 32 of file cp_vehicle_command.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), and publisher_.
Referenced by arm(), disarm(), forceArm(), land(), setOffboardMode(), and takeoff().


| void cl_px4_mr::CpVehicleCommand::setOffboardMode | ( | ) |
Definition at line 74 of file cp_vehicle_command.cpp.
References sendCommand().
Referenced by cl_px4_mr::CbTakeOff::onEntry().


| void cl_px4_mr::CpVehicleCommand::takeoff | ( | float | altitude | ) |
Definition at line 81 of file cp_vehicle_command.cpp.
References sendCommand().

|
private |
Definition at line 44 of file cp_vehicle_command.hpp.
Referenced by onInitialize(), and sendCommand().