#include <mavros_uas.h>
Public Types | |
typedef std::lock_guard < std::recursive_mutex > | lock_guard |
typedef std::unique_lock < std::recursive_mutex > | unique_lock |
Public Member Functions | |
bool | cmode_from_str (std::string cmode_str, uint32_t &custom_mode) |
Lookup custom mode for given string. | |
tf::Vector3 | get_attitude_angular_velocity () |
Get Attitude angular velocity vector. | |
tf::Vector3 | get_attitude_linear_acceleration () |
Get Attitude linear acceleration vector. | |
tf::Quaternion | get_attitude_orientation () |
Get Attitude orientation quaternion. | |
enum MAV_AUTOPILOT | get_autopilot () |
Returns autopilot type. | |
bool | get_connection_status () |
Returns connection status. | |
double | get_gps_altitude () |
double | get_gps_eph () |
double | get_gps_epv () |
double | get_gps_latitude () |
double | get_gps_longitude () |
bool | get_gps_status () |
uint8_t | get_tgt_component () |
Return communication target component. | |
uint8_t | get_tgt_system () |
Return communication target system. | |
uint64_t | get_time_offset (void) |
enum MAV_TYPE | get_type () |
Returns vehicle type. | |
bool | is_ardupilotmega () |
Check that FCU is APM. | |
bool | is_px4 () |
Check that FCU is PX4. | |
void | set_attitude_angular_velocity (tf::Vector3 &vec) |
Store Attitude angular velocity vector. | |
void | set_attitude_linear_acceleration (tf::Vector3 &vec) |
Store Attitude linear acceleration vector. | |
void | set_attitude_orientation (tf::Quaternion &quat) |
Store Attitude orientation quaternion. | |
void | set_gps_llae (double latitude, double longitude, double altitude, double eph, double epv) |
Store GPS Lat/Long/Alt and EPH/EPV data. | |
void | set_gps_status (bool fix_status_) |
void | set_tgt (uint8_t sys, uint8_t comp) |
void | set_time_offset (uint64_t offset) |
void | stop (void) |
std::string | str_mode_v10 (uint8_t base_mode, uint32_t custom_mode) |
Represent FCU mode as string. | |
UAS () | |
void | update_connection_status (bool conn_) |
void | update_heartbeat (uint8_t type_, uint8_t autopilot_) |
~UAS () | |
Public Attributes | |
mavconn::MAVConnInterface::Ptr | fcu_link |
MAVLink FCU device conection. | |
boost::signals2::signal< void(bool)> | sig_connection_changed |
This signal emit when status was changed. | |
Private Attributes | |
tf::Vector3 | angular_velocity |
std::atomic< uint8_t > | autopilot |
std::atomic< bool > | connected |
std::atomic< bool > | fix_status |
double | gps_altitude |
double | gps_eph |
double | gps_epv |
double | gps_latitude |
double | gps_longitude |
tf::Vector3 | linear_acceleration |
std::recursive_mutex | mutex |
Compute FCU message time from time_boot_ms field. | |
tf::Quaternion | orientation |
uint8_t | target_component |
uint8_t | target_system |
std::atomic< uint64_t > | time_offset |
std::atomic< uint8_t > | type |
UAS for plugins.
This class stores some useful data and provides fcu connection, mode stringify utilities.
Currently it stores:
Definition at line 76 of file mavros_uas.h.