From 690dc9052a51e9010f675869468de140b306de9b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 24 Feb 2012 17:23:08 +1100 Subject: [PATCH] GCS: force scalar type in copy_name() this enables access to compass offsets over MAVLink --- ArduCopter/GCS_Mavlink.pde | 2 +- ArduPlane/GCS_Mavlink.pde | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index aca9d9922c..4a45b181b2 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1647,7 +1647,7 @@ GCS_MAVLINK::queued_param_send() value = vp->cast_to_float(_queued_parameter_type); char param_name[ONBOARD_PARAM_NAME_LENGTH]; - vp->copy_name(param_name, sizeof(param_name)); + vp->copy_name(param_name, sizeof(param_name), true); mavlink_msg_param_value_send( chan, diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index a301b9fa2c..312144a886 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -2000,7 +2000,7 @@ GCS_MAVLINK::queued_param_send() value = vp->cast_to_float(_queued_parameter_type); char param_name[ONBOARD_PARAM_NAME_LENGTH]; - vp->copy_name(param_name, sizeof(param_name)); + vp->copy_name(param_name, sizeof(param_name), true); mavlink_msg_param_value_send( chan,