adapt Mavlink_compat.h to AP_Param

This commit is contained in:
Andrew Tridgell 2012-02-12 19:17:08 +11:00
parent 570399ff98
commit e01af5885f
1 changed files with 5 additions and 5 deletions

View File

@ -53,15 +53,15 @@
#define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode #define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode
#define mavlink_waypoint_set_current_t mavlink_mission_set_current_t #define mavlink_waypoint_set_current_t mavlink_mission_set_current_t
static uint8_t mav_var_type(AP_Meta_class::Type_id t) static uint8_t mav_var_type(enum ap_var_type t)
{ {
if (t == AP_Var::k_typeid_int8) { if (t == AP_PARAM_INT8) {
return MAV_VAR_INT8; return MAV_VAR_INT8;
} }
if (t == AP_Var::k_typeid_int16) { if (t == AP_PARAM_INT16) {
return MAV_VAR_INT16; return MAV_VAR_INT16;
} }
if (t == AP_Var::k_typeid_int32) { if (t == AP_PARAM_INT32) {
return MAV_VAR_INT32; return MAV_VAR_INT32;
} }
// treat any others as float // treat any others as float
@ -72,7 +72,7 @@ static uint8_t mav_var_type(AP_Meta_class::Type_id t)
#else // MAVLINK10 #else // MAVLINK10
static uint8_t mav_var_type(AP_Meta_class::Type_id t) static uint8_t mav_var_type(enum ap_var_type t)
{ {
return 0; return 0;
} }