Browse Source

GCS_MAVLink: use MAV_PARAM_TYPE for sending parameter messages

... rather than mavlink_message_type_t
master
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
49493676ea
  1. 12
      libraries/GCS_MAVLink/GCS_MAVLink.cpp
  2. 4
      libraries/GCS_MAVLink/GCS_MAVLink.h
  3. 6
      libraries/GCS_MAVLink/GCS_Param.cpp

12
libraries/GCS_MAVLink/GCS_MAVLink.cpp

@ -78,20 +78,20 @@ void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan) @@ -78,20 +78,20 @@ void GCS_MAVLINK::set_channel_private(mavlink_channel_t _chan)
mavlink_active &= ~mask;
}
// return a MAVLink variable type given a AP_Param type
uint8_t mav_var_type(enum ap_var_type t)
// return a MAVLink parameter type given a AP_Param type
MAV_PARAM_TYPE mav_param_type(enum ap_var_type t)
{
if (t == AP_PARAM_INT8) {
return MAVLINK_TYPE_INT8_T;
return MAV_PARAM_TYPE_INT8;
}
if (t == AP_PARAM_INT16) {
return MAVLINK_TYPE_INT16_T;
return MAV_PARAM_TYPE_INT16;
}
if (t == AP_PARAM_INT32) {
return MAVLINK_TYPE_INT32_T;
return MAV_PARAM_TYPE_INT32;
}
// treat any others as float
return MAVLINK_TYPE_FLOAT;
return MAV_PARAM_TYPE_REAL32;
}

4
libraries/GCS_MAVLink/GCS_MAVLink.h

@ -72,8 +72,8 @@ uint16_t comm_get_txspace(mavlink_channel_t chan); @@ -72,8 +72,8 @@ uint16_t comm_get_txspace(mavlink_channel_t chan);
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#include "include/mavlink/v2.0/ardupilotmega/mavlink.h"
// return a MAVLink variable type given a AP_Param type
uint8_t mav_var_type(enum ap_var_type t);
// return a MAVLink parameter type given a AP_Param type
MAV_PARAM_TYPE mav_param_type(enum ap_var_type t);
// lock and unlock a channel, for multi-threaded mavlink send
void comm_send_lock(mavlink_channel_t chan);

6
libraries/GCS_MAVLink/GCS_Param.cpp

@ -81,7 +81,7 @@ GCS_MAVLINK::queued_param_send() @@ -81,7 +81,7 @@ GCS_MAVLINK::queued_param_send()
chan,
param_name,
_queued_parameter->cast_to_float(_queued_parameter_type),
mav_var_type(_queued_parameter_type),
mav_param_type(_queued_parameter_type),
_queued_parameter_count,
_queued_parameter_index);
@ -312,7 +312,7 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f @@ -312,7 +312,7 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f
_chan,
param_name,
param_value,
mav_var_type(param_type),
mav_param_type(param_type),
AP_Param::count_parameters(),
-1);
}
@ -391,7 +391,7 @@ bool GCS_MAVLINK::send_parameter_reply(void) @@ -391,7 +391,7 @@ bool GCS_MAVLINK::send_parameter_reply(void)
reply.chan,
reply.param_name,
reply.value,
mav_var_type(reply.p_type),
mav_param_type(reply.p_type),
reply.count,
reply.param_index);

Loading…
Cancel
Save