vehicle_status.msg: delete unused mavlink stuff

The MAV_TYPE enum was not in sync with the mavlink specs anymore. It
makes therefore sense to remove the duplication and include the correct
mavlink header file where it is needed.
Also, error counts which are not populated, can be scrapped.
This commit is contained in:
Julian Oes
2016-02-24 10:10:50 +00:00
parent 5f3a23a253
commit 74072dbe74
3 changed files with 20 additions and 61 deletions

View File

@@ -64,6 +64,7 @@
#include "commander_helper.h"
#include "DevMgr.hpp"
#include "mavlink/v1.0/common/mavlink.h" // For MAV_TYPE
using namespace DriverFramework;
@@ -77,23 +78,22 @@ static const int ERROR = -1;
bool is_multirotor(const struct vehicle_status_s *current_status)
{
return ((current_status->system_type == vehicle_status_s::VEHICLE_TYPE_QUADROTOR) ||
(current_status->system_type == vehicle_status_s::VEHICLE_TYPE_HEXAROTOR) ||
(current_status->system_type == vehicle_status_s::VEHICLE_TYPE_OCTOROTOR) ||
(current_status->system_type == vehicle_status_s::VEHICLE_TYPE_TRICOPTER));
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));
}
bool is_rotary_wing(const struct vehicle_status_s *current_status)
{
return is_multirotor(current_status) || (current_status->system_type == vehicle_status_s::VEHICLE_TYPE_HELICOPTER)
|| (current_status->system_type == vehicle_status_s::VEHICLE_TYPE_COAXIAL);
return is_multirotor(current_status) || (current_status->system_type == MAV_TYPE_HELICOPTER)
|| (current_status->system_type == MAV_TYPE_COAXIAL);
}
bool is_vtol(const struct vehicle_status_s * current_status) {
return (current_status->system_type == vehicle_status_s::VEHICLE_TYPE_VTOL_DUOROTOR ||
current_status->system_type == vehicle_status_s::VEHICLE_TYPE_VTOL_QUADROTOR ||
current_status->system_type == vehicle_status_s::VEHICLE_TYPE_VTOL_HEXAROTOR ||
current_status->system_type == vehicle_status_s::VEHICLE_TYPE_VTOL_OCTOROTOR);
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);
}
static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message