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

#include <cp_vehicle_command.hpp>

Inheritance diagram for cl_px4_mr::CpVehicleCommand:
Inheritance graph
Collaboration diagram for cl_px4_mr::CpVehicleCommand:
Collaboration graph

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
 
ISmaccStateMachinegetStateMachine ()
 
- Protected Attributes inherited from smacc2::ISmaccComponent
ISmaccStateMachinestateMachine_
 
ISmaccClientowner_
 

Detailed Description

Definition at line 24 of file cp_vehicle_command.hpp.

Constructor & Destructor Documentation

◆ CpVehicleCommand()

cl_px4_mr::CpVehicleCommand::CpVehicleCommand ( )

Definition at line 20 of file cp_vehicle_command.cpp.

20{}

◆ ~CpVehicleCommand()

cl_px4_mr::CpVehicleCommand::~CpVehicleCommand ( )
virtual

Definition at line 22 of file cp_vehicle_command.cpp.

22{}

Member Function Documentation

◆ arm()

void cl_px4_mr::CpVehicleCommand::arm ( )

Definition at line 58 of file cp_vehicle_command.cpp.

59{
60 sendCommand(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0f);
61}
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)

References sendCommand().

Referenced by cl_px4_mr::CbArmPX4::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ disarm()

void cl_px4_mr::CpVehicleCommand::disarm ( )

Definition at line 69 of file cp_vehicle_command.cpp.

70{
71 sendCommand(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 0.0f);
72}

References sendCommand().

Referenced by cl_px4_mr::CbDisarmPX4::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ forceArm()

void cl_px4_mr::CpVehicleCommand::forceArm ( )

Definition at line 63 of file cp_vehicle_command.cpp.

64{
65 // param2 = 21196 bypasses pre-arm checks (useful for SITL without RC/GCS)
66 sendCommand(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_COMPONENT_ARM_DISARM, 1.0f, 21196.0f);
67}

References sendCommand().

Referenced by cl_px4_mr::CbArmPX4::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ land()

void cl_px4_mr::CpVehicleCommand::land ( )

Definition at line 79 of file cp_vehicle_command.cpp.

79{ sendCommand(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_NAV_LAND); }

References sendCommand().

Referenced by cl_px4_mr::CbLand::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onInitialize()

void cl_px4_mr::CpVehicleCommand::onInitialize ( )
overridevirtual

Reimplemented from smacc2::ISmaccComponent.

Definition at line 24 of file cp_vehicle_command.cpp.

25{
26 auto node = this->getNode();
27 publisher_ = node->create_publisher<px4_msgs::msg::VehicleCommand>(
28 "/fmu/in/vehicle_command", rclcpp::QoS(1).best_effort());
29 RCLCPP_INFO(getLogger(), "CpVehicleCommand: publisher created on /fmu/in/vehicle_command");
30}
rclcpp::Publisher< px4_msgs::msg::VehicleCommand >::SharedPtr publisher_
rclcpp::Logger getLogger() const
rclcpp::Node::SharedPtr getNode()

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), and publisher_.

Here is the call graph for this function:

◆ sendCommand()

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.

35{
36 auto node = this->getNode();
37 px4_msgs::msg::VehicleCommand msg;
38 msg.timestamp = node->get_clock()->now().nanoseconds() / 1000;
39 msg.command = command;
40 msg.param1 = param1;
41 msg.param2 = param2;
42 msg.param3 = param3;
43 msg.param4 = param4;
44 msg.param5 = param5;
45 msg.param6 = param6;
46 msg.param7 = param7;
47 msg.target_system = 1;
48 msg.target_component = 1;
49 msg.source_system = 1;
50 msg.source_component = 1;
51 msg.from_external = true;
52 publisher_->publish(msg);
53 RCLCPP_INFO(
54 getLogger(), "CpVehicleCommand: sent command %u (p1=%.1f p2=%.1f p7=%.1f)", command, param1,
55 param2, param7);
56}

References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), and publisher_.

Referenced by arm(), disarm(), forceArm(), land(), setOffboardMode(), and takeoff().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setOffboardMode()

void cl_px4_mr::CpVehicleCommand::setOffboardMode ( )

Definition at line 74 of file cp_vehicle_command.cpp.

75{
76 sendCommand(px4_msgs::msg::VehicleCommand::VEHICLE_CMD_DO_SET_MODE, 1.0f, 6.0f);
77}

References sendCommand().

Referenced by cl_px4_mr::CbTakeOff::onEntry().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ takeoff()

void cl_px4_mr::CpVehicleCommand::takeoff ( float altitude)

Definition at line 81 of file cp_vehicle_command.cpp.

82{
84 px4_msgs::msg::VehicleCommand::VEHICLE_CMD_NAV_TAKEOFF, 0.0f, 0.0f, 0.0f, 0.0f, 0.0, 0.0,
85 altitude);
86}

References sendCommand().

Here is the call graph for this function:

Member Data Documentation

◆ publisher_

rclcpp::Publisher<px4_msgs::msg::VehicleCommand>::SharedPtr cl_px4_mr::CpVehicleCommand::publisher_
private

Definition at line 44 of file cp_vehicle_command.hpp.

Referenced by onInitialize(), and sendCommand().


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