AutoAPMS
Resilient Robot Mission Management
Loading...
Searching...
No Matches
VehicleCommandClient Class Reference

#include <auto_apms_px4/vehicle_command_client.hpp>

Public Types

enum class  FlightMode : uint8_t {
  Takeoff = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_TAKEOFF , Land = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LAND , Hold = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_LOITER , RTL = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_RTL ,
  Mission = px4_msgs::msg::VehicleStatus::NAVIGATION_STATE_AUTO_MISSION
}
 
enum  SendCommandResult : uint8_t { ACCEPTED , REJECTED , TIMEOUT }
 

Public Member Functions

 VehicleCommandClient (rclcpp::Node &node, const std::chrono::milliseconds &command_timeout=std::chrono::milliseconds(500))
 
SendCommandResult SyncSendVehicleCommand (uint32_t command, float param1=NAN, float param2=NAN, float param3=NAN, float param4=NAN, float param5=NAN, float param6=NAN, float param7=NAN) const
 
SendCommandResult SyncSendVehicleCommand (const VehicleCommand &cmd) const
 
bool Arm () const
 
bool Disarm () const
 
bool StartMission () const
 
bool Takeoff (float altitude_amsl_m, float heading_rad=NAN) const
 
bool Land () const
 
bool SyncActivateFlightMode (uint8_t mode_id) const
 
bool SyncActivateFlightMode (const FlightMode &mode) const
 
bool SyncActivateFlightMode (const px4_ros2::ModeBase *const mode_ptr) const
 

Detailed Description

Definition at line 29 of file vehicle_command_client.hpp.

Member Enumeration Documentation

◆ FlightMode

enum class FlightMode : uint8_t
strong
Enumerator
Takeoff 
Land 
Hold 
RTL 
Mission 

Definition at line 34 of file vehicle_command_client.hpp.

◆ SendCommandResult

enum SendCommandResult : uint8_t
Enumerator
ACCEPTED 
REJECTED 
TIMEOUT 

Definition at line 43 of file vehicle_command_client.hpp.

Constructor & Destructor Documentation

◆ VehicleCommandClient()

VehicleCommandClient ( rclcpp::Node & node,
const std::chrono::milliseconds & command_timeout = std::chrono::milliseconds(500) )
explicit

Definition at line 37 of file vehicle_command_client.cpp.

Member Function Documentation

◆ SyncSendVehicleCommand() [1/2]

VehicleCommandClient::SendCommandResult SyncSendVehicleCommand ( uint32_t command,
float param1 = NAN,
float param2 = NAN,
float param3 = NAN,
float param4 = NAN,
float param5 = NAN,
float param6 = NAN,
float param7 = NAN ) const

Definition at line 48 of file vehicle_command_client.cpp.

◆ SyncSendVehicleCommand() [2/2]

VehicleCommandClient::SendCommandResult SyncSendVehicleCommand ( const VehicleCommand & cmd) const

Definition at line 68 of file vehicle_command_client.cpp.

◆ Arm()

bool Arm ( ) const

Definition at line 126 of file vehicle_command_client.cpp.

◆ Disarm()

bool Disarm ( ) const

Definition at line 131 of file vehicle_command_client.cpp.

◆ StartMission()

bool StartMission ( ) const

(Re)starts the uploaded mission plan.

If you want to resume a mission, use SyncActivateFlightMode(FlightMode::Mission) instead.

Definition at line 136 of file vehicle_command_client.cpp.

◆ Takeoff()

bool Takeoff ( float altitude_amsl_m,
float heading_rad = NAN ) const

Definition at line 141 of file vehicle_command_client.cpp.

◆ Land()

bool Land ( ) const

Definition at line 148 of file vehicle_command_client.cpp.

◆ SyncActivateFlightMode() [1/3]

bool SyncActivateFlightMode ( uint8_t mode_id) const

Definition at line 153 of file vehicle_command_client.cpp.

◆ SyncActivateFlightMode() [2/3]

bool SyncActivateFlightMode ( const FlightMode & mode) const

Definition at line 158 of file vehicle_command_client.cpp.

◆ SyncActivateFlightMode() [3/3]

bool SyncActivateFlightMode ( const px4_ros2::ModeBase *const mode_ptr) const

Definition at line 163 of file vehicle_command_client.cpp.


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