From 922338e98261321b7439a0d5674c37ce7ec0c667 Mon Sep 17 00:00:00 2001
From: Michael Oborne <mich146@hotmail.com>
Date: Sun, 6 May 2012 10:59:17 +0800
Subject: [PATCH] AP - fix attitude level hil mavlink 1.0 issue

---
 ArduPlane/GCS_Mavlink.pde | 2 +-
 ArduPlane/Parameters.pde  | 3 ---
 2 files changed, 1 insertion(+), 4 deletions(-)

diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde
index c1313c37b..8076e925e 100644
--- a/ArduPlane/GCS_Mavlink.pde
+++ b/ArduPlane/GCS_Mavlink.pde
@@ -1955,7 +1955,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
 			mavlink_hil_state_t packet;
 			mavlink_msg_hil_state_decode(msg, &packet);
 			
-			float vel = sqrt((packet.vx * packet.vx) + (packet.vy * packet.vy));
+			float vel = sqrt((packet.vx * (float)packet.vx) + (packet.vy * (float)packet.vy));
 			float cog = wrap_360(ToDeg(atan2(packet.vx, packet.vy)) * 100);
 			
             // set gps hil sensor
diff --git a/ArduPlane/Parameters.pde b/ArduPlane/Parameters.pde
index c7ff129f4..6bb4ea37a 100644
--- a/ArduPlane/Parameters.pde
+++ b/ArduPlane/Parameters.pde
@@ -29,7 +29,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
     // @Param: KFF_PTCHCOMP
 	// @DisplayName: Pitch Compensation
 	// @Description: Adds pitch input to compensate for the loss of lift due to roll control.
-	// @Units: Percent
 	// @Range: 0 1
 	// @Increment: 0.1
 	// @User: Advanced
@@ -38,7 +37,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
     // @Param: KFF_RDDRMIX
 	// @DisplayName: Rudder Mix
 	// @Description: The ammount of rudder mix to apply during aileron movement
-	// @Units: Percent
 	// @Range: 0 1
 	// @Increment: 0.1
 	// @User: Standard
@@ -70,7 +68,6 @@ static const AP_Param::Info var_info[] PROGMEM = {
     // @Param: XTRK_GAIN_SC
 	// @DisplayName: Crosstrack Gain
 	// @Description: The scale between distance off the line and angle to meet the line (in Degrees * 100)
-	// @Units: Degrees
 	// @Range: 0 2000
 	// @Increment: 1
 	// @User: Standard
-- 
GitLab