Commander: MAVLink is an off-vehicle API we should not depend internally on

This commit is contained in:
Lorenz Meier 2016-08-02 14:54:16 +02:00
parent 437221bec2
commit 670b0f7c6d

View File

@ -62,8 +62,6 @@
#include <drivers/drv_led.h>
#include <drivers/drv_rgbled.h>
#include <v2.0/common/mavlink.h> // For MAV_TYPE
#include "commander_helper.h"
#include "DevMgr.hpp"
@ -75,30 +73,44 @@ using namespace DriverFramework;
#endif
static const int ERROR = -1;
#define VEHICLE_TYPE_QUADROTOR 2
#define VEHICLE_TYPE_COAXIAL 3
#define VEHICLE_TYPE_HELICOPTER 4
#define VEHICLE_TYPE_HEXAROTOR 13
#define VEHICLE_TYPE_OCTOROTOR 14
#define VEHICLE_TYPE_TRICOPTER 15
#define VEHICLE_TYPE_VTOL_DUOROTOR 19
#define VEHICLE_TYPE_VTOL_QUADROTOR 20
#define VEHICLE_TYPE_VTOL_TILTROTOR 21
#define VEHICLE_TYPE_VTOL_RESERVED2 22
#define VEHICLE_TYPE_VTOL_RESERVED3 23
#define VEHICLE_TYPE_VTOL_RESERVED4 24
#define VEHICLE_TYPE_VTOL_RESERVED5 25
#define BLINK_MSG_TIME 700000 // 3 fast blinks
bool is_multirotor(const struct vehicle_status_s *current_status)
{
return ((current_status->system_type == MAV_TYPE_QUADROTOR) ||
(current_status->system_type == MAV_TYPE_HEXAROTOR) ||
(current_status->system_type == MAV_TYPE_OCTOROTOR) ||
(current_status->system_type == MAV_TYPE_TRICOPTER));
return ((current_status->system_type == VEHICLE_TYPE_QUADROTOR) ||
(current_status->system_type == VEHICLE_TYPE_HEXAROTOR) ||
(current_status->system_type == VEHICLE_TYPE_OCTOROTOR) ||
(current_status->system_type == VEHICLE_TYPE_TRICOPTER));
}
bool is_rotary_wing(const struct vehicle_status_s *current_status)
{
return is_multirotor(current_status) || (current_status->system_type == MAV_TYPE_HELICOPTER)
|| (current_status->system_type == MAV_TYPE_COAXIAL);
return is_multirotor(current_status) || (current_status->system_type == VEHICLE_TYPE_HELICOPTER)
|| (current_status->system_type == VEHICLE_TYPE_COAXIAL);
}
bool is_vtol(const struct vehicle_status_s * current_status) {
return (current_status->system_type == MAV_TYPE_VTOL_DUOROTOR ||
current_status->system_type == MAV_TYPE_VTOL_QUADROTOR ||
current_status->system_type == MAV_TYPE_VTOL_TILTROTOR ||
current_status->system_type == MAV_TYPE_VTOL_RESERVED2 ||
current_status->system_type == MAV_TYPE_VTOL_RESERVED3 ||
current_status->system_type == MAV_TYPE_VTOL_RESERVED4 ||
current_status->system_type == MAV_TYPE_VTOL_RESERVED5);
return (current_status->system_type == VEHICLE_TYPE_VTOL_DUOROTOR ||
current_status->system_type == VEHICLE_TYPE_VTOL_QUADROTOR ||
current_status->system_type == VEHICLE_TYPE_VTOL_TILTROTOR ||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED2 ||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED3 ||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED4 ||
current_status->system_type == VEHICLE_TYPE_VTOL_RESERVED5);
}
static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message