MAVROS node implementation. More...
MAVROS node implementation.
#define UAS_FCU | ( | uasobjptr | ) | ((uasobjptr)->fcu_link) |
helper accessor to FCU link interface
Definition at line 39 of file mavros_uas.h.
#define UAS_PACK_CHAN | ( | uasobjptr | ) |
UAS_FCU(uasobjptr)->get_system_id(), \ UAS_FCU(uasobjptr)->get_component_id(), \ UAS_FCU(uasobjptr)->get_channel()
helper for mavlink_msg_*_pack_chan()
Filler for first arguments of *_pack_chan functions.
Definition at line 47 of file mavros_uas.h.
#define UAS_PACK_TGT | ( | uasobjptr | ) |
(uasobjptr)->get_tgt_system(), \ (uasobjptr)->get_tgt_component()
helper for pack messages with target fields
Filler for target_system, target_component fields.
Definition at line 57 of file mavros_uas.h.
typedef std::lock_guard<std::recursive_mutex> mavros::UAS::lock_guard |
Definition at line 78 of file mavros_uas.h.
typedef std::unique_lock<std::recursive_mutex> mavros::UAS::unique_lock |
Definition at line 79 of file mavros_uas.h.
MAIN_MODE_MANUAL | |
MAIN_MODE_ALTCTL | |
MAIN_MODE_POSCTL | |
MAIN_MODE_AUTO | |
MAIN_MODE_ACRO | |
MAIN_MODE_OFFBOARD |
Definition at line 28 of file px4_custom_mode.h.
SUB_MODE_AUTO_READY | |
SUB_MODE_AUTO_TAKEOFF | |
SUB_MODE_AUTO_LOITER | |
SUB_MODE_AUTO_MISSION | |
SUB_MODE_AUTO_RTL | |
SUB_MODE_AUTO_LAND | |
SUB_MODE_AUTO_RTGS |
Definition at line 37 of file px4_custom_mode.h.
void mavros::MavRos::add_plugin | ( | std::string & | pl_name | ) | [private] |
bool mavros::MavRos::check_in_blacklist | ( | std::string & | pl_name | ) | [private] |
bool UAS::cmode_from_str | ( | std::string | cmode_str, |
uint32_t & | custom_mode | ||
) |
Lookup custom mode for given string.
Complimentary to str_mode_v10()
[in] | cmode_str | string representation of mode |
[out] | custom_mode | decoded value |
px4::custom_mode::custom_mode | ( | ) | [inline] |
Definition at line 55 of file px4_custom_mode.h.
px4::custom_mode::custom_mode | ( | uint32_t | val | ) | [inline, explicit] |
Definition at line 58 of file px4_custom_mode.h.
constexpr px4::custom_mode::custom_mode | ( | uint8_t | mm, |
uint8_t | sm | ||
) | [inline] |
Definition at line 61 of file px4_custom_mode.h.
constexpr uint32_t px4::define_mode | ( | enum custom_mode::MAIN_MODE | mm, |
uint8_t | sm = 0 |
||
) |
helper function to define any mode as uint32_t constant
mm | main mode |
sm | sub mode (currently used only in auto mode) |
Definition at line 75 of file px4_custom_mode.h.
constexpr uint32_t px4::define_mode_auto | ( | enum custom_mode::SUB_MODE_AUTO | sm | ) |
helper function to define auto mode as uint32_t constant
Same as define_mode(custom_mode::MAIN_MODE_AUTO, sm)
sm | auto sub mode |
Definition at line 87 of file px4_custom_mode.h.
tf::Vector3 mavros::UAS::get_attitude_angular_velocity | ( | ) | [inline] |
Get Attitude angular velocity vector.
Definition at line 171 of file mavros_uas.h.
tf::Vector3 mavros::UAS::get_attitude_linear_acceleration | ( | ) | [inline] |
Get Attitude linear acceleration vector.
Definition at line 189 of file mavros_uas.h.
tf::Quaternion mavros::UAS::get_attitude_orientation | ( | ) | [inline] |
Get Attitude orientation quaternion.
Definition at line 207 of file mavros_uas.h.
enum MAV_AUTOPILOT mavros::UAS::get_autopilot | ( | ) | [inline] |
Returns autopilot type.
Definition at line 139 of file mavros_uas.h.
bool mavros::UAS::get_connection_status | ( | ) | [inline] |
Returns connection status.
Definition at line 124 of file mavros_uas.h.
double mavros::UAS::get_gps_altitude | ( | ) | [inline] |
Definition at line 252 of file mavros_uas.h.
double mavros::UAS::get_gps_eph | ( | ) | [inline] |
Definition at line 257 of file mavros_uas.h.
double mavros::UAS::get_gps_epv | ( | ) | [inline] |
Definition at line 262 of file mavros_uas.h.
double mavros::UAS::get_gps_latitude | ( | ) | [inline] |
Definition at line 242 of file mavros_uas.h.
double mavros::UAS::get_gps_longitude | ( | ) | [inline] |
Definition at line 247 of file mavros_uas.h.
bool mavros::UAS::get_gps_status | ( | ) | [inline] |
Definition at line 271 of file mavros_uas.h.
uint8_t mavros::UAS::get_tgt_component | ( | ) | [inline] |
Return communication target component.
Definition at line 156 of file mavros_uas.h.
uint8_t mavros::UAS::get_tgt_system | ( | ) | [inline] |
Return communication target system.
Definition at line 149 of file mavros_uas.h.
uint64_t mavros::UAS::get_time_offset | ( | void | ) | [inline] |
Definition at line 280 of file mavros_uas.h.
enum MAV_TYPE mavros::UAS::get_type | ( | ) | [inline] |
Returns vehicle type.
Definition at line 131 of file mavros_uas.h.
bool mavros::UAS::is_ardupilotmega | ( | ) | [inline] |
Check that FCU is APM.
Definition at line 289 of file mavros_uas.h.
bool mavros::UAS::is_px4 | ( | ) | [inline] |
Check that FCU is PX4.
Definition at line 296 of file mavros_uas.h.
void mavros::MavRos::log_connect_change | ( | bool | connected | ) | [private] |
void mavros::MavRos::mavlink_pub_cb | ( | const mavlink_message_t * | mmsg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [private] |
void mavros::MavRos::mavlink_sub_cb | ( | const Mavlink::ConstPtr & | rmsg | ) | [private] |
MavlinkDiag::MavlinkDiag | ( | std::string | name | ) | [explicit] |
Definition at line 28 of file mavlink_diag.cpp.
MavRos::MavRos | ( | const ros::NodeHandle & | nh_ | ) | [explicit] |
Definition at line 34 of file mavros.cpp.
void mavros::MavRos::plugin_route_cb | ( | const mavlink_message_t * | mmsg, |
uint8_t | sysid, | ||
uint8_t | compid | ||
) | [private] |
void MavlinkDiag::run | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [virtual] |
Implements diagnostic_updater::DiagnosticTask.
Definition at line 34 of file mavlink_diag.cpp.
void mavros::UAS::set_attitude_angular_velocity | ( | tf::Vector3 & | vec | ) | [inline] |
Store Attitude angular velocity vector.
[in] | vec | angular velocity [ENU, body-fixed] |
Definition at line 180 of file mavros_uas.h.
void mavros::UAS::set_attitude_linear_acceleration | ( | tf::Vector3 & | vec | ) | [inline] |
Store Attitude linear acceleration vector.
[in] | vec | linear acceleration [ENU, body-fixed] |
Definition at line 198 of file mavros_uas.h.
void mavros::UAS::set_attitude_orientation | ( | tf::Quaternion & | quat | ) | [inline] |
Store Attitude orientation quaternion.
[in] | quat | orientation [ENU, body-fixed] |
Definition at line 216 of file mavros_uas.h.
void mavros::MavlinkDiag::set_connection_status | ( | bool | connected | ) | [inline] |
Definition at line 45 of file mavlink_diag.h.
void mavros::UAS::set_gps_llae | ( | double | latitude, |
double | longitude, | ||
double | altitude, | ||
double | eph, | ||
double | epv | ||
) | [inline] |
Store GPS Lat/Long/Alt and EPH/EPV data.
[in] | latitude | in deg |
[in] | longitude | in deg |
[in] | altitude | in m |
[in] | eph | in m |
[in] | epv | in m |
Definition at line 232 of file mavros_uas.h.
void mavros::UAS::set_gps_status | ( | bool | fix_status_ | ) | [inline] |
Definition at line 267 of file mavros_uas.h.
void mavros::MavlinkDiag::set_mavconn | ( | const mavconn::MAVConnInterface::Ptr & | link | ) | [inline] |
Definition at line 41 of file mavlink_diag.h.
void mavros::UAS::set_tgt | ( | uint8_t | sys, |
uint8_t | comp | ||
) | [inline] |
Definition at line 160 of file mavros_uas.h.
void mavros::UAS::set_time_offset | ( | uint64_t | offset | ) | [inline] |
Definition at line 276 of file mavros_uas.h.
void mavros::MavRos::spin | ( | ) |
void mavros::MavRos::startup_px4_usb_quirk | ( | void | ) | [private] |
std::string UAS::str_mode_v10 | ( | uint8_t | base_mode, |
uint32_t | custom_mode | ||
) |
void mavros::MavRos::terminate_cb | ( | ) | [private] |
void mavros::UAS::update_connection_status | ( | bool | conn_ | ) | [inline] |
Update autopilot connection status (every HEARTBEAT/conn_timeout)
Definition at line 107 of file mavros_uas.h.
void mavros::UAS::update_heartbeat | ( | uint8_t | type_, |
uint8_t | autopilot_ | ||
) | [inline] |
Update autopilot type on every HEARTBEAT
Definition at line 99 of file mavros_uas.h.
mavros::MavRos::~MavRos | ( | ) | [inline] |
mavros::UAS::~UAS | ( | ) | [inline] |
Definition at line 82 of file mavros_uas.h.
struct { ... } |
tf::Vector3 mavros::UAS::angular_velocity [private] |
Definition at line 343 of file mavros_uas.h.
std::atomic<uint8_t> mavros::UAS::autopilot [private] |
Definition at line 339 of file mavros_uas.h.
std::atomic<bool> mavros::UAS::connected [private] |
Definition at line 342 of file mavros_uas.h.
uint32_t px4::custom_mode::data |
Definition at line 52 of file px4_custom_mode.h.
Definition at line 53 of file px4_custom_mode.h.
MAVLink FCU device conection.
Definition at line 92 of file mavros_uas.h.
MavlinkDiag mavros::MavRos::fcu_link_diag [private] |
std::atomic<bool> mavros::UAS::fix_status [private] |
Definition at line 351 of file mavros_uas.h.
MavlinkDiag mavros::MavRos::gcs_link_diag [private] |
double mavros::UAS::gps_altitude [private] |
Definition at line 348 of file mavros_uas.h.
double mavros::UAS::gps_eph [private] |
Definition at line 349 of file mavros_uas.h.
double mavros::UAS::gps_epv [private] |
Definition at line 350 of file mavros_uas.h.
double mavros::UAS::gps_latitude [private] |
Definition at line 346 of file mavros_uas.h.
double mavros::UAS::gps_longitude [private] |
Definition at line 347 of file mavros_uas.h.
bool mavros::MavlinkDiag::is_connected [private] |
Definition at line 52 of file mavlink_diag.h.
unsigned int mavros::MavlinkDiag::last_drop_count [private] |
Definition at line 51 of file mavlink_diag.h.
tf::Vector3 mavros::UAS::linear_acceleration [private] |
Definition at line 344 of file mavros_uas.h.
std::vector<mavplugin::MavRosPlugin::Ptr> mavros::MavRos::loaded_plugins [private] |
uint8_t px4::custom_mode::main_mode |
Definition at line 49 of file px4_custom_mode.h.
uint8_t { ... } ::main_mode |
Definition at line 49 of file px4_custom_mode.h.
UAS mavros::MavRos::mav_uas [private] |
ros::Publisher mavros::MavRos::mavlink_pub [private] |
ros::Subscriber mavros::MavRos::mavlink_sub [private] |
std::array<mavconn::MAVConnInterface::MessageSig, 256> mavros::MavRos::message_route_table [private] |
std::recursive_mutex mavros::UAS::mutex [private] |
Compute FCU message time from time_boot_ms field.
Uses time_offset for calculation
Definition at line 337 of file mavros_uas.h.
ros::NodeHandle mavros::MavRos::node_handle [private] |
tf::Quaternion mavros::UAS::orientation [private] |
Definition at line 345 of file mavros_uas.h.
std::vector<std::string> mavros::MavRos::plugin_blacklist [private] |
uint16_t { ... } ::reserved |
Definition at line 48 of file px4_custom_mode.h.
uint16_t px4::custom_mode::reserved |
Definition at line 48 of file px4_custom_mode.h.
boost::signals2::signal<void(bool)> mavros::UAS::sig_connection_changed |
This signal emit when status was changed.
bool | connection status |
Definition at line 119 of file mavros_uas.h.
uint8_t px4::custom_mode::sub_mode |
Definition at line 50 of file px4_custom_mode.h.
uint8_t { ... } ::sub_mode |
Definition at line 50 of file px4_custom_mode.h.
uint8_t mavros::UAS::target_component [private] |
Definition at line 341 of file mavros_uas.h.
uint8_t mavros::UAS::target_system [private] |
Definition at line 340 of file mavros_uas.h.
std::atomic<uint64_t> mavros::UAS::time_offset [private] |
Definition at line 352 of file mavros_uas.h.
std::atomic<uint8_t> mavros::UAS::type [private] |
Definition at line 338 of file mavros_uas.h.
Definition at line 50 of file mavlink_diag.h.