MAVROS Plugin context. More...
#include <array>
#include <mutex>
#include <atomic>
#include <Eigen/Eigen>
#include <Eigen/Geometry>
#include <tf2_ros/transform_listener.h>
#include <tf2_ros/transform_broadcaster.h>
#include <diagnostic_updater/diagnostic_updater.h>
#include <mavconn/interface.h>
#include <sensor_msgs/Imu.h>
#include <sensor_msgs/NavSatFix.h>
Go to the source code of this file.
Classes | |
class | mavros::UAS |
UAS for plugins. More... | |
Namespaces | |
namespace | mavros |
Defines | |
#define | UAS_DIAG(uasobjptr) ((uasobjptr)->diag_updater) |
helper accessor to diagnostic updater | |
#define | UAS_FCU(uasobjptr) ((uasobjptr)->fcu_link) |
helper accessor to FCU link interface | |
#define | UAS_PACK_CHAN(uasobjptr) |
helper for mavlink_msg_*_pack_chan() | |
#define | UAS_PACK_TGT(uasobjptr) |
helper for pack messages with target fields |
MAVROS Plugin context.
Definition in file mavros_uas.h.