Pārlūkot izejas kodu

主要修改了对应限制Dshort的修改以及mavlink的修改

danny wang 1 gadu atpakaļ
vecāks
revīzija
efe42ec6d3

+ 16 - 13
ArduSub/GCS_Mavlink.cpp

@@ -316,12 +316,12 @@ const AP_Param::GroupInfo GCS_MAVLINK_Parameters::var_info[] = {
 };
 	
 static const ap_message STREAM_RAW_SENSORS_msgs[] = {
-	MSG_RAW_IMU,
-	MSG_SCALED_IMU2,
-	MSG_SCALED_IMU3,
+	//MSG_RAW_IMU,
+	//MSG_SCALED_IMU2,
+	//MSG_SCALED_IMU3,
 	MSG_SCALED_PRESSURE,
-	MSG_SCALED_PRESSURE2,
-	MSG_SCALED_PRESSURE3,
+	//MSG_SCALED_PRESSURE2,
+	//MSG_SCALED_PRESSURE3,
 	MSG_SENSOR_OFFSETS
 };
 static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
@@ -340,32 +340,35 @@ static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
 static const ap_message STREAM_POSITION_msgs[] = {
    // MSG_LOCATION,
    // MSG_LOCAL_POSITION
+   MSG_SET_SLAVE_PARAMETER
 };
 static const ap_message STREAM_RC_CHANNELS_msgs[] = {
-	MSG_SERVO_OUTPUT_RAW,
-	MSG_RC_CHANNELS,
-	MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
+	//MSG_SERVO_OUTPUT_RAW,
+	//MSG_RC_CHANNELS,
+	//MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
+	MSG_ROV_STATE_MONITORING
 };
 static const ap_message STREAM_EXTRA1_msgs[] = {
 	MSG_ATTITUDE,
 	//MSG_SIMSTATE,
 	//MSG_AHRS2,
-	MSG_AHRS3,
+	//MSG_AHRS3,
 	MSG_PID_TUNING
 };
 static const ap_message STREAM_EXTRA2_msgs[] = {
 	
 	//MSG_VFR_HUD
 	//MSG_ROTATION_MATRIX_ARRAY,
-	MSG_ROV_STATE_MONITORING,
-	MSG_SET_SLAVE_PARAMETER,
+	MSG_ROV_MOTOR_TEMP,
+	//MSG_ROV_STATE_MONITORING,
+	//MSG_SET_SLAVE_PARAMETER,
 	MSG_MOTOR_SPEED,
 	MSG_HV_REG_GET
    
 };
 static const ap_message STREAM_EXTRA3_msgs[] = {
 	//MSG_AHRS,
-	MSG_HWSTATUS,
+	//MSG_HWSTATUS,
 	MSG_SYSTEM_TIME,
    // MSG_RANGEFINDER,
    // MSG_DISTANCE_SENSOR,
@@ -384,7 +387,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
 #if RPM_ENABLED == ENABLED
 	//MSG_RPM,
 #endif
-	MSG_ESC_TELEMETRY,
+	//MSG_ESC_TELEMETRY,
 };
 static const ap_message STREAM_PARAMS_msgs[] = {
 	MSG_NEXT_PARAM

+ 1 - 0
ArduSub/Sub.cpp

@@ -45,6 +45,7 @@ Sub::Sub()
     // init sensor error logging flags
     sensor_health.baro = true;
     sensor_health.compass = true;
+	clean_thruster_help =1;
 
 #if CONFIG_HAL_BOARD != HAL_BOARD_SITL
     failsafe.pilot_input = true;

+ 1 - 0
ArduSub/Sub.h

@@ -821,6 +821,7 @@ public:
 	void getyaw(void);
 	void getgain(void);
 	//---------track----------------
+	uint8_t clean_thruster_help;
 	int16_t brushleft;//左毛刷
 	int16_t brushright;//右毛刷
 	int16_t motor1_speed_target;//履带电机1 目标PWM

+ 1 - 1
ArduSub/control_althold.cpp

@@ -80,7 +80,7 @@ void Sub::handle_attitude()
 	   }else if(prepare_state == Vertical)
 	   	{
 		   pitch_input = 8000;
-		   target_roll = ((float)channel_yaw->get_control_in()*0.5);
+		   target_roll = -((float)channel_yaw->get_control_in()*0.5);
 		   
 		   target_yaw = 0;
 	   }

+ 59 - 45
ArduSub/control_clean.cpp

@@ -1,9 +1,9 @@
 #include "Sub.h"
 //目标姿态
 
-float maxspeed = 51.0;
-float minspeed = 31.0;
-float maxerrorspeed = 31.0;
+float maxspeed = 800.0;
+float minspeed = 280.0;
+float maxerrorspeed = 310.0;
 
 //float turnspeed  = maxspeed - maxerror_f;
 
@@ -89,14 +89,31 @@ void Sub::clean_run()
 		
 		rov_message.pressure_level = int(PressLevel);
 		
-		motors.set_forward(0.0);	//右侧摇杆,前推为+,后推为- 右履带的前进后退
-		motors.set_lateral(0.0);//右侧摇杆 左推-,右推+
-		motors.set_yaw(0.0);//左侧摇杆左推- 右推+
-		motors.set_roll(0.0);
-   		//motors.set_pitch(0.0);
-   	   //motors.set_roll(channel_lateral->norm_input());//(channel_roll->norm_input());//左右移动改为roll
-       motors.set_pitch((0.5-channel_throttle->norm_input())*2);//(channel_pitch->norm_input());//上升下潜改为pitch
-    	motors.set_yaw(0.0);
+		if (clean_thruster_help==1)
+		{
+			float pitch_throttle = (0.5-channel_throttle->norm_input())*2;
+			float yaw_throttle = channel_yaw->norm_input();
+			if (fabsf(yaw_throttle)>fabsf(pitch_throttle))
+			{
+				pitch_throttle = 0.0;
+			}else{
+				yaw_throttle =0.0;
+			}
+			
+			motors.set_forward(0.0);	//右侧摇杆,前推为+,后推为- 右履带的前进后退
+			motors.set_yaw(0.0);//左侧摇杆左推- 右推+
+			
+			motors.set_pitch(pitch_throttle);
+			
+		}else{
+			motors.set_forward(0.0);	//右侧摇杆,前推为+,后推为- 右履带的前进后退
+			motors.set_yaw(0.0);//左侧摇杆左推- 右推+
+			motors.set_pitch(0.0);
+		}
+
+	    motors.set_roll(0.0);//(channel_roll->norm_input());//左右移动改为roll
+		motors.set_lateral(0.0);//(channel_lateral->norm_input());
+
 	   static int j = 0;
 		 j++;
 		 if(j>800)
@@ -104,16 +121,16 @@ void Sub::clean_run()
 			 // gcs().send_text(MAV_SEVERITY_INFO, " track_limit %f\n",(float)rov_control.track_limit);
 			  j=0;
 		 }
-		 maxspeed = (float)rov_control.track_limit;
+		 maxspeed = (float)rov_control.track_limit*10;
 		 
 
-		 if (maxspeed<31.0)
+		 if (maxspeed<280.0)
 		{
-			 maxspeed = 31.0;
+			 maxspeed = 280.0;
 		}
-		 if(maxspeed>91.0)
+		 if(maxspeed>910.0)
 		{
-			 maxspeed = 91.0;
+			 maxspeed = 910.0;
 		}
 		//turnspeed  = maxspeed - maxerror_f;
 		 
@@ -143,7 +160,7 @@ void Sub::autoclean_flag_chose(void){
 	}
 
 }
-float maxspeed_set=50.0;
+float maxspeed_set=800.0;
 
 void Sub::clean_net_joystick(void)
 {
@@ -154,21 +171,31 @@ void Sub::clean_net_joystick(void)
 	int16_t motors1 =startval;
 	int16_t motors2 =startval;
 	
-	minspeed =(float)SRV_Channels::srv_channel(15)->get_output_max()/100;// 暂时用来做最小速度   -----最小水深
-	maxerrorspeed =(float)SRV_Channels::srv_channel(15)->get_output_min()/100;//两个履带最大差速 ----------最深距离 厘米 
-	maxspeed_set = (float)SRV_Channels::srv_channel(15)->get_trim()/100;
+	minspeed =(float)SRV_Channels::srv_channel(15)->get_output_max()/10;// 暂时用来做最小速度   -----最小水深
+	maxerrorspeed =(float)SRV_Channels::srv_channel(15)->get_output_min()/10;//两个履带最大差速 ----------最深距离 厘米 
+	maxspeed_set = (float)SRV_Channels::srv_channel(15)->get_trim()/10;
+
 	if(maxspeed_set<maxspeed)
 	{
 		maxspeed = maxspeed_set;
 	}
-	
+
 	if(handclean == TRUE ){
 		
 		//计算电机的 手动转速
+		float pitch_throttle = (0.5-channel_throttle->norm_input())*2;
+		float yaw_throttle = channel_yaw->norm_input();
+		if (fabsf(yaw_throttle)>fabsf(pitch_throttle))
+		{
+				//pitch_throttle = 0.0;
+				
+			_turn = Constrate1(channel_yaw->norm_input());//转向 右+左-,+右转 左履带增,-左转 右lvdai+
+		}else{
+				_turn =0.0;
+		}
 
 		left  = Constrate1(channel_forward->norm_input());//   
-		_turn = Constrate1(channel_yaw->norm_input());//转向 右+左-,+右转 左履带增,-左转 右lvdai+
-
+		
 		motors1 = (int16_t)((left*maxspeed +_turn*maxerrorspeed));//右履带  //第一台高压电机 
 		motors2 = (int16_t)((left*maxspeed -_turn*maxerrorspeed));//左履带
 		if(_turn>0.1)
@@ -228,14 +255,7 @@ void Sub::clean_net_joystick(void)
 		motors1=constrain_int16(motors1,-(int16_t)minspeedlimit_back,(int16_t)maxspeed);
 		motors2=constrain_int16(motors2,-(int16_t)minspeedlimit_back,(int16_t)maxspeed);
 		
-		static int f = 0;
-		f++;
-		if(f>800)
-		{
-			
-			//gcs().send_text(MAV_SEVERITY_INFO, "minspeed %d %d,%d,%d",(int)minspeed,(int)maxerrorspeed,(int)maxspeed,(int)minspeedlimit);
-			f=0;
-		}
+
 
 
 		  //左摇杆前进后退的指示---------------
@@ -262,8 +282,8 @@ void Sub::clean_net_joystick(void)
 			track_head_gd = (float)ahrs.yaw_sensor/100;//to show 20210611
 			
 			
-			slowly_speed1(motor1_speed_target,motors1,1,3);
-			slowly_speed2(motor2_speed_target,motors2,1,3);
+			slowly_speed1(motor1_speed_target,motors1,4,1);
+			slowly_speed2(motor2_speed_target,motors2,4,1);
 			track_motor_arm =3;//left or right
 
 			
@@ -271,8 +291,8 @@ void Sub::clean_net_joystick(void)
 		else{
 			//纯手动控制
 			if(clean_mode == 0){
-				slowly_speed1(motor1_speed_target,motors1,1,3);
-				slowly_speed2(motor2_speed_target,motors2,1,3);
+				slowly_speed1(motor1_speed_target,motors1,4,1);
+				slowly_speed2(motor2_speed_target,motors2,4,1);
 
 
 	
@@ -281,6 +301,7 @@ void Sub::clean_net_joystick(void)
 			}
 
 		}
+
 	}
 
 }
@@ -392,8 +413,8 @@ void Sub::motor_toCan(void)
 
    if(mav_motor_speed.motorTest == 1)//电机测试模式
    {
-	   motors.motor_to_can[8]  = mav_motor_speed.Ltrack;//切换成上位机控制 左履带
-	   motors.motor_to_can[9] = mav_motor_speed.Rtrack;//右履带
+	   motors.motor_to_can[8]  = mav_motor_speed.Ltrack*2;//切换成上位机控制 左履带
+	   motors.motor_to_can[9] = mav_motor_speed.Rtrack*2;//右履带
    }else{
 	   if(control_mode == CLEAN){
 		motors.motor_to_can[8]	 = motor1_speed_target;//飞控自己的履带
@@ -404,14 +425,7 @@ void Sub::motor_toCan(void)
 	   }
    }
 	  
-	 	  static int j = 0;
-	  j++;
-	  if(j>400)
-	  {
-		  
-		  // gcs().send_text(MAV_SEVERITY_INFO, " motor_to_can %d %d ,%d,%d\n",motors.motor_to_can[8],motors.motor_to_can[9]);
-		   j=0;
-	  }
+
  }
 void Sub::clean_sidenet_auto(void)
 {

+ 4 - 4
ArduSub/joystick.cpp

@@ -670,13 +670,13 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
 				PressLevel_f = 1.0;//
 			}else if (PressLevel == forth){
 				PressLevel = fifth;
-				PressLevel_f = 2.75;//
+				PressLevel_f = 4.75;//
 			}else if(PressLevel == fifth){
 				PressLevel = no;
 				PressLevel_f = 5.0;	//
 			}else if(PressLevel == no){
 				PressLevel = sixth;
-				PressLevel_f = 7.25;//
+				PressLevel_f = 5.25;//
 			}else if (PressLevel == sixth){
 				PressLevel = seventh;
 				PressLevel_f = 9.0;//
@@ -712,13 +712,13 @@ void Sub::handle_jsbutton_press(uint8_t button, bool shift, bool held)
 				 PressLevel_f = 9.0;//
 			 }else if (PressLevel == seventh){
 				 PressLevel = sixth;
-				  PressLevel_f = 7.25;//
+				  PressLevel_f = 5.25;//
 			 }else if(PressLevel == sixth){
 				 PressLevel = no;
 				  PressLevel_f = 5.0;//
 			 }else if(PressLevel == no){
 				 PressLevel = fifth;
-				 PressLevel_f = 2.75; //
+				 PressLevel_f = 4.75; //
 			 }else if (PressLevel == fifth){
 				 PressLevel = forth;
 				  PressLevel_f = 1.0;//	 

+ 4 - 3
libraries/AP_Motors/AP_Motors6DOF.cpp

@@ -229,7 +229,7 @@ void AP_Motors6DOF::output_min()
 
 #define ThrustScale 1000
 #define hv_min 251
-#define hv_max 1850
+#define hv_max 2000
 int16_t AP_Motors6DOF::calc_thrust_to_HV(float thrust_in,int8_t i)
 { 
 	  int16_t thrust = 0;
@@ -392,8 +392,8 @@ void AP_Motors6DOF::output_to_Dshot()
 		//将上位机转发过来的,转换成Dshot协议并使用CAN 转发
 		if(mav_motor_speed.motorTest == 1)
 		{//测试模式上位机直接控制 仅仅控制6个推进器
-			 motor_to_can[0] = mav_motor_speed.motor1*1000;
-			 motor_to_can[1] = mav_motor_speed.motor2*1000;
+			 motor_to_can[0] = (int16_t)(mav_motor_speed.motor1*1000);
+			 motor_to_can[1] = (int16_t)(mav_motor_speed.motor2*1000);
 			 motor_to_can[2] = mav_motor_speed.motor3;
 			 motor_to_can[3] = mav_motor_speed.motor4;
 			 motor_to_can[4] = mav_motor_speed.motor5;
@@ -420,6 +420,7 @@ void AP_Motors6DOF::output_to_Dshot()
 
 		}
 
+
 }
 
 int16_t AP_Motors6DOF::calc_thrust_to_pwm(float thrust_in) const

+ 13 - 13
libraries/AP_UAVCAN/AP_UAVCAN.cpp

@@ -324,7 +324,7 @@ static void motor_res_st_cb(const uavcan::ReceivedDataStructure<uavcan::equipmen
 	////
 		voltage48V = msg.rpm0;
 		temperature_power = msg.rpm1;
-		motor_stall_state.all = msg.rpm2;//所有电机的堵转
+		motor_stall_state.all = msg.rpm2;//所有电机的堵转// 履带没有堵转了
 
 		static int16_t c5  = 0;
 		c5++;
@@ -405,7 +405,7 @@ static void thruster1GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equi
 	
 	
 
-	gcs().send_text(MAV_SEVERITY_WARNING, "thruster3 %x .",(uint32_t)hv_reg_get.data[0]);
+	//gcs().send_text(MAV_SEVERITY_WARNING, "thruster3 %x .",(uint32_t)hv_reg_get.data[0]);
 }
 static void Thruster1GetRegs_cb0(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::HighVoltThruster1GetRegs>& msg ){
 			thruster1GetRegs_cb(msg,0);
@@ -435,7 +435,7 @@ static void thruster2GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equi
 	
 	
 
-	gcs().send_text(MAV_SEVERITY_WARNING, "thruster4 %x .",(uint32_t)hv_reg_get.data[0]);
+	//gcs().send_text(MAV_SEVERITY_WARNING, "thruster4 %x .",(uint32_t)hv_reg_get.data[0]);
 
 
 
@@ -466,7 +466,7 @@ static void thruster3GetRegs_cb(const uavcan::ReceivedDataStructure<uavcan::equi
 	
 	
 
-	gcs().send_text(MAV_SEVERITY_WARNING, "thruster5 %x .",(uint32_t)hv_reg_get.data[0]);
+	//gcs().send_text(MAV_SEVERITY_WARNING, "thruster5 %x .",(uint32_t)hv_reg_get.data[0]);
 
 
 	
@@ -506,12 +506,12 @@ struct HVmotor haoye2={0,0,0,0,0,0};
 	//if(msg.CODE == 0x0A){
 		
 		//int16_t speedmes = buffer[4]+(buffer[5]<<8);
-		static int8_t per = 0;
+		static int16_t per = 0;
 		per++;
-		if (per>100)
+		if (per>150)
 		{
 			per = 0;
-			gcs().send_text(MAV_SEVERITY_INFO, "HV3 %d %d %d %d",(int)Thruster1.voltage,(int)Thruster1.speedref,(int)Thruster1.temperature,(int)Thruster1.motortemperature);
+			gcs().send_text(MAV_SEVERITY_INFO, "HV3 %d %d %d",(int)Thruster1.voltage,(int)Thruster1.speedref,(int)Thruster1.temperature);
 			}
 			
 	//}
@@ -548,12 +548,12 @@ static void Thruster2timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equ
 	//if(msg.CODE == 0x0A){
 		
 		//int16_t speedmes = buffer[4]+(buffer[5]<<8);
-		static int8_t per = 0;
+		static int16_t per = 0;
 		per++;
-		if (per>100)
+		if (per>150)
 		{
 			per = 0;
-			gcs().send_text(MAV_SEVERITY_INFO, "HV4 %d %d %d %d",(int)Thruster2.voltage,(int)Thruster2.speedref,(int)Thruster2.temperature,(int)Thruster2.motortemperature);
+			gcs().send_text(MAV_SEVERITY_INFO, "HV4 %d %d %d",(int)Thruster2.voltage,(int)Thruster2.speedref,(int)Thruster2.temperature);
 		}
 			
 	//}
@@ -589,12 +589,12 @@ static void Thruster3timeback_cb(const uavcan::ReceivedDataStructure<uavcan::equ
 		//if(msg.CODE == 0x0A){
 		
 		//int16_t speedmes = buffer[4]+(buffer[5]<<8);
-		static int8_t per = 0;
+		static int16_t per = 0;
 		per++;
-		if (per>100)
+		if (per>150)
 		{
 			per = 0;
-			gcs().send_text(MAV_SEVERITY_INFO, "HV5 %d %d %d %d",(int)Thruster3.voltage,(int)Thruster3.speedref,(int)Thruster3.temperature,(int)Thruster3.motortemperature);
+			gcs().send_text(MAV_SEVERITY_INFO, "HV5 %d %d %d ",(int)Thruster3.voltage,(int)Thruster3.speedref,(int)Thruster3.temperature);
 		}
 			
 	//}

+ 27 - 1
libraries/GCS_MAVLink/GCS_Common.cpp

@@ -1017,6 +1017,7 @@ mavlink_data64_t rov_message3;
 extern mavlink_set_slave_parameter_t get_stm32_param;
 extern mavlink_hv_reg_get_t hv_reg_get;
 extern uint8_t get_stm32_param_buf[7];
+mavlink_rov_motor_temp_t rov_motor_temp = {0,0,0,0,0,0,0,0,0,0};
 
 int countper = 0;
 uint16_t lvtruster_fault(uint8_t i,uint16_t motor_stall_flag,uint32_t propellerblock_flag){
@@ -1059,6 +1060,11 @@ void GCS_MAVLINK::update_send()
 			rov_message.deep = fabsf(sub.barometer.get_altitude());//深度
 			rov_message.temp = (float)(uavcan.temperature_48Vpower)/10;//传过来的是*100的?
 			rov_message.motor_block_flag =  (uint16_t)(uavcan.motor_stall_flag);
+
+
+			rov_message.track_fault_flag[0] = (uint16_t)0;
+			rov_message.track_fault_flag[1] = (uint16_t)0;
+
 			rov_message.motor_twine_flag[0] = lvtruster_fault(0,uavcan.motor_stall_flag,uavcan.propellerblock_flag);//(uint16_t)(uavcan.propellerblock_flag & 0x0000000F)|((uavcan.motor_stall_flag&0x0001)<<4);
 			rov_message.motor_twine_flag[1] = lvtruster_fault(1,uavcan.motor_stall_flag,uavcan.propellerblock_flag);//(uint16_t)((uavcan.propellerblock_flag & 0x000000F0)>>4)|((uavcan.motor_stall_flag&0x0002)<<3);
 			rov_message.motor_twine_flag[2] = (uint16_t)(uavcan.HVmotor1.fault);
@@ -1069,6 +1075,8 @@ void GCS_MAVLINK::update_send()
 			rov_message.motor_twine_flag[7] = 0;//(uint16_t)((uavcan.propellerblock_flag & 0xF0000000)>>28)|((uavcan.motor_stall_flag&0x0080)>>3);
 
 
+			rov_message.track_power[0] = 0;
+			rov_message.track_power[1] = 0;
 
 			rov_message.motor_power[0] = 0;
 			rov_message.motor_power[1] = 0;
@@ -1076,6 +1084,22 @@ void GCS_MAVLINK::update_send()
 			rov_message.motor_power[3] = (uint16_t)(uavcan.HVmotor2.torqueIQ);
 			rov_message.motor_power[4] = (uint16_t)(uavcan.HVmotor3.torqueIQ);
 			rov_message.motor_power[5] = 0;
+			rov_message.motor_power[5] = 0;
+			rov_message.motor_power[6] = 0;
+			rov_message.motor_power[7] = 0;
+
+
+			rov_motor_temp.track_temperature[0] = 0;
+			rov_motor_temp.track_temperature[1] = 0;
+			
+			rov_motor_temp.motor_temperature[0] = 0;
+			rov_motor_temp.motor_temperature[1] = 0;
+			rov_motor_temp.motor_temperature[2] = (uint16_t)(uavcan.HVmotor1.motortemperature);
+			rov_motor_temp.motor_temperature[3] = (uint16_t)(uavcan.HVmotor2.motortemperature);
+			rov_motor_temp.motor_temperature[4] = (uint16_t)(uavcan.HVmotor2.motortemperature);
+			rov_motor_temp.motor_temperature[5] = 0;
+			rov_motor_temp.motor_temperature[6] = 0;
+			rov_motor_temp.motor_temperature[7] = 0;
 
 
 			get_stm32_param.number = get_stm32_param_buf[0];
@@ -4179,7 +4203,9 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
     bool ret = true;
 
     switch(id) {
-		
+	case MSG_ROV_MOTOR_TEMP:
+		mavlink_msg_rov_motor_temp_send_struct(chan,&rov_motor_temp);
+		break;			
 	case MSG_ROV_STATE_MONITORING:
 		mavlink_msg_rov_state_monitoring_send_struct(chan,&rov_message);
 		break;

+ 1 - 0
libraries/GCS_MAVLink/ap_message.h

@@ -58,6 +58,7 @@ enum ap_message : uint8_t {
     MSG_PID_TUNING,
     MSG_VIBRATION,
     MSG_RPM,
+    MSG_ROV_MOTOR_TEMP,
     MSG_HV_REG_GET,
     MSG_ROV_STATE_MONITORING,
     MSG_MOTOR_SPEED,

+ 1681 - 0
modules/mavlink/message_definitions/v1.0/ardupilotmega.bak

@@ -0,0 +1,1681 @@
+<?xml version="1.0"?>
+<mavlink>
+  <include>common.xml</include>
+  <!-- Vendors -->
+  <include>uAvionix.xml</include>
+  <include>icarous.xml</include>
+  <dialect>2</dialect>
+  <!-- Note that APM specific messages should use the command id range from 150 to 250, to leave plenty of room for growth of common.xml If you prototype a message here, then you should consider if it is general enough to move into common.xml later -->
+  <enums>
+    <enum name="ACCELCAL_VEHICLE_POS">
+      <entry value="1" name="ACCELCAL_VEHICLE_POS_LEVEL"/>
+      <entry value="2" name="ACCELCAL_VEHICLE_POS_LEFT"/>
+      <entry value="3" name="ACCELCAL_VEHICLE_POS_RIGHT"/>
+      <entry value="4" name="ACCELCAL_VEHICLE_POS_NOSEDOWN"/>
+      <entry value="5" name="ACCELCAL_VEHICLE_POS_NOSEUP"/>
+      <entry value="6" name="ACCELCAL_VEHICLE_POS_BACK"/>
+      <entry value="16777215" name="ACCELCAL_VEHICLE_POS_SUCCESS"/>
+      <entry value="16777216" name="ACCELCAL_VEHICLE_POS_FAILED"/>
+    </enum>
+    <!-- ardupilot specific MAV_CMD_* commands -->
+    <enum name="MAV_CMD">
+      <entry value="211" name="MAV_CMD_DO_GRIPPER">
+        <description>Mission command to operate EPM gripper.</description>
+        <param index="1">Gripper number (a number from 1 to max number of grippers on the vehicle).</param>
+        <param index="2">Gripper action (0=release, 1=grab. See GRIPPER_ACTIONS enum).</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="212" name="MAV_CMD_DO_AUTOTUNE_ENABLE">
+        <description>Enable/disable autotune.</description>
+        <param index="1">Enable (1: enable, 0:disable).</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="83" name="MAV_CMD_NAV_ALTITUDE_WAIT">
+        <description>Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up.</description>
+        <param index="1">Altitude (m).</param>
+        <param index="2">Descent speed (m/s).</param>
+        <param index="3">Wiggle Time (s).</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42000" name="MAV_CMD_POWER_OFF_INITIATED">
+        <description>A system wide power-off event has been initiated.</description>
+        <param index="1">Empty.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <!-- MAV_CMD_SOLO_BTN_* are here to provide vendor-specific support for 3DR Solo until a better solution is found to atomically make multiple commands with control flow -->
+      <entry value="42001" name="MAV_CMD_SOLO_BTN_FLY_CLICK">
+        <description>FLY button has been clicked.</description>
+        <param index="1">Empty.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42002" name="MAV_CMD_SOLO_BTN_FLY_HOLD">
+        <description>FLY button has been held for 1.5 seconds.</description>
+        <param index="1">Takeoff altitude.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42003" name="MAV_CMD_SOLO_BTN_PAUSE_CLICK">
+        <description>PAUSE button has been clicked.</description>
+        <param index="1">1 if Solo is in a shot mode, 0 otherwise.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42004" name="MAV_CMD_FIXED_MAG_CAL">
+        <description>Magnetometer calibration based on fixed position
+        in earth field given by inclination, declination and intensity.</description>
+        <param index="1">MagDeclinationDegrees.</param>
+        <param index="2">MagInclinationDegrees.</param>
+        <param index="3">MagIntensityMilliGauss.</param>
+        <param index="4">YawDegrees.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42005" name="MAV_CMD_FIXED_MAG_CAL_FIELD">
+        <description>Magnetometer calibration based on fixed expected field values in milliGauss.</description>
+        <param index="1">FieldX.</param>
+        <param index="2">FieldY.</param>
+        <param index="3">FieldZ.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42424" name="MAV_CMD_DO_START_MAG_CAL">
+        <description>Initiate a magnetometer calibration.</description>
+        <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
+        <param index="2">Automatically retry on failure (0=no retry, 1=retry).</param>
+        <param index="3">Save without user input (0=require input, 1=autosave).</param>
+        <param index="4">Delay (seconds).</param>
+        <param index="5">Autoreboot (0=user reboot, 1=autoreboot).</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42425" name="MAV_CMD_DO_ACCEPT_MAG_CAL">
+        <description>Initiate a magnetometer calibration.</description>
+        <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42426" name="MAV_CMD_DO_CANCEL_MAG_CAL">
+        <description>Cancel a running magnetometer calibration.</description>
+        <param index="1">uint8_t bitmask of magnetometers (0 means all).</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42429" name="MAV_CMD_ACCELCAL_VEHICLE_POS">
+        <description>Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in.</description>
+        <param index="1">Position, one of the ACCELCAL_VEHICLE_POS enum values.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42428" name="MAV_CMD_DO_SEND_BANNER">
+        <description>Reply with the version banner.</description>
+        <param index="1">Empty.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42427" name="MAV_CMD_SET_FACTORY_TEST_MODE">
+        <description>Command autopilot to get into factory test/diagnostic mode.</description>
+        <param index="1">0 means get out of test mode, 1 means get into test mode.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42501" name="MAV_CMD_GIMBAL_RESET">
+        <description>Causes the gimbal to reset and boot as if it was just powered on.</description>
+        <param index="1">Empty.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42502" name="MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS">
+        <description>Reports progress and success or failure of gimbal axis calibration procedure.</description>
+        <param index="1">Gimbal axis we're reporting calibration progress for.</param>
+        <param index="2">Current calibration progress for this axis, 0x64=100%.</param>
+        <param index="3">Status of the calibration.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42503" name="MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION">
+        <description>Starts commutation calibration on the gimbal.</description>
+        <param index="1">Empty.</param>
+        <param index="2">Empty.</param>
+        <param index="3">Empty.</param>
+        <param index="4">Empty.</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42505" name="MAV_CMD_GIMBAL_FULL_RESET">
+        <description>Erases gimbal application and parameters.</description>
+        <param index="1">Magic number.</param>
+        <param index="2">Magic number.</param>
+        <param index="3">Magic number.</param>
+        <param index="4">Magic number.</param>
+        <param index="5">Magic number.</param>
+        <param index="6">Magic number.</param>
+        <param index="7">Magic number.</param>
+      </entry>
+      <entry value="42600" name="MAV_CMD_DO_WINCH">
+        <description>Command to operate winch.</description>
+        <param index="1">Winch number (0 for the default winch, otherwise a number from 1 to max number of winches on the vehicle).</param>
+        <param index="2">Action (0=relax, 1=relative length control, 2=rate control. See WINCH_ACTIONS enum.).</param>
+        <param index="3">Release length (cable distance to unwind in meters, negative numbers to wind in cable).</param>
+        <param index="4">Release rate (meters/second).</param>
+        <param index="5">Empty.</param>
+        <param index="6">Empty.</param>
+        <param index="7">Empty.</param>
+      </entry>
+      <entry value="42650" name="MAV_CMD_FLASH_BOOTLOADER">
+        <description>Update the bootloader</description>
+        <param index="1">Empty</param>
+        <param index="2">Empty</param>
+        <param index="3">Empty</param>
+        <param index="4">Empty</param>
+        <param index="5">Magic number - set to 290876 to actually flash</param>
+        <param index="6">Empty</param>
+        <param index="7">Empty</param>
+      </entry>
+      <entry value="42651" name="MAV_CMD_BATTERY_RESET" hasLocation="false" isDestination="false">
+        <description>Reset battery capacity for batteries that accumulate consumed battery via integration.</description>
+        <param index="1" label="battery mask">Bitmask of batteries to reset. Least significant bit is for the first battery.</param>
+        <param index="2" label="percentage" minValue="0" maxValue="100" increment="1">Battery percentage remaining to set.</param>
+        <param index="3">Reserved, send 0</param>
+        <param index="4">Reserved, send 0</param>
+        <param index="5">Reserved, send 0</param>
+        <param index="6">Reserved, send 0</param>
+        <param index="7">Reserved, send 0</param>
+      </entry>
+    </enum>
+    <!-- AP_Limits Enums -->
+    <enum name="LIMITS_STATE">
+      <entry value="0" name="LIMITS_INIT">
+        <description>Pre-initialization.</description>
+      </entry>
+      <entry value="1" name="LIMITS_DISABLED">
+        <description>Disabled.</description>
+      </entry>
+      <entry value="2" name="LIMITS_ENABLED">
+        <description>Checking limits.</description>
+      </entry>
+      <entry value="3" name="LIMITS_TRIGGERED">
+        <description>A limit has been breached.</description>
+      </entry>
+      <entry value="4" name="LIMITS_RECOVERING">
+        <description>Taking action e.g. Return/RTL.</description>
+      </entry>
+      <entry value="5" name="LIMITS_RECOVERED">
+        <description>We're no longer in breach of a limit.</description>
+      </entry>
+    </enum>
+    <!-- AP_Limits Modules - power of 2 (1,2,4,8,16,32 etc) so we can send as bitfield -->
+    <enum name="LIMIT_MODULE">
+      <entry value="1" name="LIMIT_GPSLOCK">
+        <description>Pre-initialization.</description>
+      </entry>
+      <entry value="2" name="LIMIT_GEOFENCE">
+        <description>Disabled.</description>
+      </entry>
+      <entry value="4" name="LIMIT_ALTITUDE">
+        <description>Checking limits.</description>
+      </entry>
+    </enum>
+    <!-- RALLY flags - power of 2 (1,2,4,8,16,32,64,128) so we can send as a bitfield -->
+    <enum name="RALLY_FLAGS">
+      <description>Flags in RALLY_POINT message.</description>
+      <entry value="1" name="FAVORABLE_WIND">
+        <description>Flag set when requiring favorable winds for landing.</description>
+      </entry>
+      <entry value="2" name="LAND_IMMEDIATELY">
+        <description>Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land.</description>
+      </entry>
+    </enum>
+    <!-- gripper action enum -->
+    <enum name="GRIPPER_ACTIONS">
+      <description>Gripper actions.</description>
+      <entry value="0" name="GRIPPER_ACTION_RELEASE">
+        <description>Gripper release cargo.</description>
+      </entry>
+      <entry value="1" name="GRIPPER_ACTION_GRAB">
+        <description>Gripper grab onto cargo.</description>
+      </entry>
+    </enum>
+    <!-- Winch action enum -->
+    <enum name="WINCH_ACTIONS">
+      <description>Winch actions.</description>
+      <entry value="0" name="WINCH_RELAXED">
+        <description>Relax winch.</description>
+      </entry>
+      <entry value="1" name="WINCH_RELATIVE_LENGTH_CONTROL">
+        <description>Winch unwinds or winds specified length of cable optionally using specified rate.</description>
+      </entry>
+      <entry value="2" name="WINCH_RATE_CONTROL">
+        <description>Winch unwinds or winds cable at specified rate in meters/seconds.</description>
+      </entry>
+    </enum>
+    <!-- Camera event types -->
+    <enum name="CAMERA_STATUS_TYPES">
+      <entry value="0" name="CAMERA_STATUS_TYPE_HEARTBEAT">
+        <description>Camera heartbeat, announce camera component ID at 1Hz.</description>
+      </entry>
+      <entry value="1" name="CAMERA_STATUS_TYPE_TRIGGER">
+        <description>Camera image triggered.</description>
+      </entry>
+      <entry value="2" name="CAMERA_STATUS_TYPE_DISCONNECT">
+        <description>Camera connection lost.</description>
+      </entry>
+      <entry value="3" name="CAMERA_STATUS_TYPE_ERROR">
+        <description>Camera unknown error.</description>
+      </entry>
+      <entry value="4" name="CAMERA_STATUS_TYPE_LOWBATT">
+        <description>Camera battery low. Parameter p1 shows reported voltage.</description>
+      </entry>
+      <entry value="5" name="CAMERA_STATUS_TYPE_LOWSTORE">
+        <description>Camera storage low. Parameter p1 shows reported shots remaining.</description>
+      </entry>
+      <entry value="6" name="CAMERA_STATUS_TYPE_LOWSTOREV">
+        <description>Camera storage low. Parameter p1 shows reported video minutes remaining.</description>
+      </entry>
+    </enum>
+    <!-- camera feedback flags, a little bit of future-proofing -->
+    <enum name="CAMERA_FEEDBACK_FLAGS">
+      <entry value="0" name="CAMERA_FEEDBACK_PHOTO">
+        <description>Shooting photos, not video.</description>
+      </entry>
+      <entry value="1" name="CAMERA_FEEDBACK_VIDEO">
+        <description>Shooting video, not stills.</description>
+      </entry>
+      <entry value="2" name="CAMERA_FEEDBACK_BADEXPOSURE">
+        <description>Unable to achieve requested exposure (e.g. shutter speed too low).</description>
+      </entry>
+      <entry value="3" name="CAMERA_FEEDBACK_CLOSEDLOOP">
+        <description>Closed loop feedback from camera, we know for sure it has successfully taken a picture.</description>
+      </entry>
+      <entry value="4" name="CAMERA_FEEDBACK_OPENLOOP">
+        <description>Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture.</description>
+      </entry>
+    </enum>
+    <!-- Gimbal payload enumerations -->
+    <enum name="MAV_MODE_GIMBAL">
+      <entry value="0" name="MAV_MODE_GIMBAL_UNINITIALIZED">
+        <description>Gimbal is powered on but has not started initializing yet.</description>
+      </entry>
+      <entry value="1" name="MAV_MODE_GIMBAL_CALIBRATING_PITCH">
+        <description>Gimbal is currently running calibration on the pitch axis.</description>
+      </entry>
+      <entry value="2" name="MAV_MODE_GIMBAL_CALIBRATING_ROLL">
+        <description>Gimbal is currently running calibration on the roll axis.</description>
+      </entry>
+      <entry value="3" name="MAV_MODE_GIMBAL_CALIBRATING_YAW">
+        <description>Gimbal is currently running calibration on the yaw axis.</description>
+      </entry>
+      <entry value="4" name="MAV_MODE_GIMBAL_INITIALIZED">
+        <description>Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter.</description>
+      </entry>
+      <entry value="5" name="MAV_MODE_GIMBAL_ACTIVE">
+        <description>Gimbal is actively stabilizing.</description>
+      </entry>
+      <entry value="6" name="MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT">
+        <description>Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command.</description>
+      </entry>
+    </enum>
+    <enum name="GIMBAL_AXIS">
+      <entry value="0" name="GIMBAL_AXIS_YAW">
+        <description>Gimbal yaw axis.</description>
+      </entry>
+      <entry value="1" name="GIMBAL_AXIS_PITCH">
+        <description>Gimbal pitch axis.</description>
+      </entry>
+      <entry value="2" name="GIMBAL_AXIS_ROLL">
+        <description>Gimbal roll axis.</description>
+      </entry>
+    </enum>
+    <enum name="GIMBAL_AXIS_CALIBRATION_STATUS">
+      <entry value="0" name="GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS">
+        <description>Axis calibration is in progress.</description>
+      </entry>
+      <entry value="1" name="GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED">
+        <description>Axis calibration succeeded.</description>
+      </entry>
+      <entry value="2" name="GIMBAL_AXIS_CALIBRATION_STATUS_FAILED">
+        <description>Axis calibration failed.</description>
+      </entry>
+    </enum>
+    <enum name="GIMBAL_AXIS_CALIBRATION_REQUIRED">
+      <entry value="0" name="GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN">
+        <description>Whether or not this axis requires calibration is unknown at this time.</description>
+      </entry>
+      <entry value="1" name="GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE">
+        <description>This axis requires calibration.</description>
+      </entry>
+      <entry value="2" name="GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE">
+        <description>This axis does not require calibration.</description>
+      </entry>
+    </enum>
+    <!-- GoPro System Enumerations -->
+    <enum name="GOPRO_HEARTBEAT_STATUS">
+      <entry value="0" name="GOPRO_HEARTBEAT_STATUS_DISCONNECTED">
+        <description>No GoPro connected.</description>
+      </entry>
+      <entry value="1" name="GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE">
+        <description>The detected GoPro is not HeroBus compatible.</description>
+      </entry>
+      <entry value="2" name="GOPRO_HEARTBEAT_STATUS_CONNECTED">
+        <description>A HeroBus compatible GoPro is connected.</description>
+      </entry>
+      <entry value="3" name="GOPRO_HEARTBEAT_STATUS_ERROR">
+        <description>An unrecoverable error was encountered with the connected GoPro, it may require a power cycle.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_HEARTBEAT_FLAGS">
+      <!-- each entry is a mask to test a bit in GOPRO_HEARTBEAT_STATUS.flags -->
+      <entry value="1" name="GOPRO_FLAG_RECORDING">
+        <description>GoPro is currently recording.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_REQUEST_STATUS">
+      <entry value="0" name="GOPRO_REQUEST_SUCCESS">
+        <description>The write message with ID indicated succeeded.</description>
+      </entry>
+      <entry value="1" name="GOPRO_REQUEST_FAILED">
+        <description>The write message with ID indicated failed.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_COMMAND">
+      <entry value="0" name="GOPRO_COMMAND_POWER">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="1" name="GOPRO_COMMAND_CAPTURE_MODE">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="2" name="GOPRO_COMMAND_SHUTTER">
+        <description>(___/Set).</description>
+      </entry>
+      <entry value="3" name="GOPRO_COMMAND_BATTERY">
+        <description>(Get/___).</description>
+      </entry>
+      <entry value="4" name="GOPRO_COMMAND_MODEL">
+        <description>(Get/___).</description>
+      </entry>
+      <entry value="5" name="GOPRO_COMMAND_VIDEO_SETTINGS">
+        <description>(Get/Set).</description>
+        <!-- Packet structure for the four values is as follows byte 0: GOPRO_RESOLUTION byte 1: GOPRO_FRAME_RATE byte 2: GOPRO_FIELD_OF_VIEW byte 3: GOPRO_VIDEO_SETTINGS_FLAGS -->
+      </entry>
+      <entry value="6" name="GOPRO_COMMAND_LOW_LIGHT">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="7" name="GOPRO_COMMAND_PHOTO_RESOLUTION">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="8" name="GOPRO_COMMAND_PHOTO_BURST_RATE">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="9" name="GOPRO_COMMAND_PROTUNE">
+        <description>(Get/Set).</description>
+      </entry>
+      <entry value="10" name="GOPRO_COMMAND_PROTUNE_WHITE_BALANCE">
+        <description>(Get/Set) Hero 3+ Only.</description>
+      </entry>
+      <entry value="11" name="GOPRO_COMMAND_PROTUNE_COLOUR">
+        <description>(Get/Set) Hero 3+ Only.</description>
+      </entry>
+      <entry value="12" name="GOPRO_COMMAND_PROTUNE_GAIN">
+        <description>(Get/Set) Hero 3+ Only.</description>
+      </entry>
+      <entry value="13" name="GOPRO_COMMAND_PROTUNE_SHARPNESS">
+        <description>(Get/Set) Hero 3+ Only.</description>
+      </entry>
+      <entry value="14" name="GOPRO_COMMAND_PROTUNE_EXPOSURE">
+        <description>(Get/Set) Hero 3+ Only.</description>
+      </entry>
+      <entry value="15" name="GOPRO_COMMAND_TIME">
+        <description>(Get/Set).</description>
+        <!-- Packet structure for the four values is as follows byte 0...3: uint32_t unix timestamp (byte 0 is MSB) -->
+      </entry>
+      <entry value="16" name="GOPRO_COMMAND_CHARGING">
+        <description>(Get/Set).</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_CAPTURE_MODE">
+      <entry value="0" name="GOPRO_CAPTURE_MODE_VIDEO">
+        <description>Video mode.</description>
+      </entry>
+      <entry value="1" name="GOPRO_CAPTURE_MODE_PHOTO">
+        <description>Photo mode.</description>
+      </entry>
+      <entry value="2" name="GOPRO_CAPTURE_MODE_BURST">
+        <description>Burst mode, Hero 3+ only.</description>
+      </entry>
+      <entry value="3" name="GOPRO_CAPTURE_MODE_TIME_LAPSE">
+        <description>Time lapse mode, Hero 3+ only.</description>
+      </entry>
+      <entry value="4" name="GOPRO_CAPTURE_MODE_MULTI_SHOT">
+        <description>Multi shot mode, Hero 4 only.</description>
+      </entry>
+      <entry value="5" name="GOPRO_CAPTURE_MODE_PLAYBACK">
+        <description>Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black.</description>
+      </entry>
+      <entry value="6" name="GOPRO_CAPTURE_MODE_SETUP">
+        <description>Playback mode, Hero 4 only.</description>
+      </entry>
+      <entry value="255" name="GOPRO_CAPTURE_MODE_UNKNOWN">
+        <description>Mode not yet known.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_RESOLUTION">
+      <entry value="0" name="GOPRO_RESOLUTION_480p">
+        <description>848 x 480 (480p).</description>
+      </entry>
+      <entry value="1" name="GOPRO_RESOLUTION_720p">
+        <description>1280 x 720 (720p).</description>
+      </entry>
+      <entry value="2" name="GOPRO_RESOLUTION_960p">
+        <description>1280 x 960 (960p).</description>
+      </entry>
+      <entry value="3" name="GOPRO_RESOLUTION_1080p">
+        <description>1920 x 1080 (1080p).</description>
+      </entry>
+      <entry value="4" name="GOPRO_RESOLUTION_1440p">
+        <description>1920 x 1440 (1440p).</description>
+      </entry>
+      <entry value="5" name="GOPRO_RESOLUTION_2_7k_17_9">
+        <description>2704 x 1440 (2.7k-17:9).</description>
+      </entry>
+      <entry value="6" name="GOPRO_RESOLUTION_2_7k_16_9">
+        <description>2704 x 1524 (2.7k-16:9).</description>
+      </entry>
+      <entry value="7" name="GOPRO_RESOLUTION_2_7k_4_3">
+        <description>2704 x 2028 (2.7k-4:3).</description>
+      </entry>
+      <entry value="8" name="GOPRO_RESOLUTION_4k_16_9">
+        <description>3840 x 2160 (4k-16:9).</description>
+      </entry>
+      <entry value="9" name="GOPRO_RESOLUTION_4k_17_9">
+        <description>4096 x 2160 (4k-17:9).</description>
+      </entry>
+      <entry value="10" name="GOPRO_RESOLUTION_720p_SUPERVIEW">
+        <description>1280 x 720 (720p-SuperView).</description>
+      </entry>
+      <entry value="11" name="GOPRO_RESOLUTION_1080p_SUPERVIEW">
+        <description>1920 x 1080 (1080p-SuperView).</description>
+      </entry>
+      <entry value="12" name="GOPRO_RESOLUTION_2_7k_SUPERVIEW">
+        <description>2704 x 1520 (2.7k-SuperView).</description>
+      </entry>
+      <entry value="13" name="GOPRO_RESOLUTION_4k_SUPERVIEW">
+        <description>3840 x 2160 (4k-SuperView).</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_FRAME_RATE">
+      <entry value="0" name="GOPRO_FRAME_RATE_12">
+        <description>12 FPS.</description>
+      </entry>
+      <entry value="1" name="GOPRO_FRAME_RATE_15">
+        <description>15 FPS.</description>
+      </entry>
+      <entry value="2" name="GOPRO_FRAME_RATE_24">
+        <description>24 FPS.</description>
+      </entry>
+      <entry value="3" name="GOPRO_FRAME_RATE_25">
+        <description>25 FPS.</description>
+      </entry>
+      <entry value="4" name="GOPRO_FRAME_RATE_30">
+        <description>30 FPS.</description>
+      </entry>
+      <entry value="5" name="GOPRO_FRAME_RATE_48">
+        <description>48 FPS.</description>
+      </entry>
+      <entry value="6" name="GOPRO_FRAME_RATE_50">
+        <description>50 FPS.</description>
+      </entry>
+      <entry value="7" name="GOPRO_FRAME_RATE_60">
+        <description>60 FPS.</description>
+      </entry>
+      <entry value="8" name="GOPRO_FRAME_RATE_80">
+        <description>80 FPS.</description>
+      </entry>
+      <entry value="9" name="GOPRO_FRAME_RATE_90">
+        <description>90 FPS.</description>
+      </entry>
+      <entry value="10" name="GOPRO_FRAME_RATE_100">
+        <description>100 FPS.</description>
+      </entry>
+      <entry value="11" name="GOPRO_FRAME_RATE_120">
+        <description>120 FPS.</description>
+      </entry>
+      <entry value="12" name="GOPRO_FRAME_RATE_240">
+        <description>240 FPS.</description>
+      </entry>
+      <entry value="13" name="GOPRO_FRAME_RATE_12_5">
+        <description>12.5 FPS.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_FIELD_OF_VIEW">
+      <entry value="0" name="GOPRO_FIELD_OF_VIEW_WIDE">
+        <description>0x00: Wide.</description>
+      </entry>
+      <entry value="1" name="GOPRO_FIELD_OF_VIEW_MEDIUM">
+        <description>0x01: Medium.</description>
+      </entry>
+      <entry value="2" name="GOPRO_FIELD_OF_VIEW_NARROW">
+        <description>0x02: Narrow.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_VIDEO_SETTINGS_FLAGS">
+      <entry value="1" name="GOPRO_VIDEO_SETTINGS_TV_MODE">
+        <description>0=NTSC, 1=PAL.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PHOTO_RESOLUTION">
+      <entry value="0" name="GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM">
+        <description>5MP Medium.</description>
+      </entry>
+      <entry value="1" name="GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM">
+        <description>7MP Medium.</description>
+      </entry>
+      <entry value="2" name="GOPRO_PHOTO_RESOLUTION_7MP_WIDE">
+        <description>7MP Wide.</description>
+      </entry>
+      <entry value="3" name="GOPRO_PHOTO_RESOLUTION_10MP_WIDE">
+        <description>10MP Wide.</description>
+      </entry>
+      <entry value="4" name="GOPRO_PHOTO_RESOLUTION_12MP_WIDE">
+        <description>12MP Wide.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PROTUNE_WHITE_BALANCE">
+      <entry value="0" name="GOPRO_PROTUNE_WHITE_BALANCE_AUTO">
+        <description>Auto.</description>
+      </entry>
+      <entry value="1" name="GOPRO_PROTUNE_WHITE_BALANCE_3000K">
+        <description>3000K.</description>
+      </entry>
+      <entry value="2" name="GOPRO_PROTUNE_WHITE_BALANCE_5500K">
+        <description>5500K.</description>
+      </entry>
+      <entry value="3" name="GOPRO_PROTUNE_WHITE_BALANCE_6500K">
+        <description>6500K.</description>
+      </entry>
+      <entry value="4" name="GOPRO_PROTUNE_WHITE_BALANCE_RAW">
+        <description>Camera Raw.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PROTUNE_COLOUR">
+      <entry value="0" name="GOPRO_PROTUNE_COLOUR_STANDARD">
+        <description>Auto.</description>
+      </entry>
+      <entry value="1" name="GOPRO_PROTUNE_COLOUR_NEUTRAL">
+        <description>Neutral.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PROTUNE_GAIN">
+      <entry value="0" name="GOPRO_PROTUNE_GAIN_400">
+        <description>ISO 400.</description>
+      </entry>
+      <entry value="1" name="GOPRO_PROTUNE_GAIN_800">
+        <description>ISO 800 (Only Hero 4).</description>
+      </entry>
+      <entry value="2" name="GOPRO_PROTUNE_GAIN_1600">
+        <description>ISO 1600.</description>
+      </entry>
+      <entry value="3" name="GOPRO_PROTUNE_GAIN_3200">
+        <description>ISO 3200 (Only Hero 4).</description>
+      </entry>
+      <entry value="4" name="GOPRO_PROTUNE_GAIN_6400">
+        <description>ISO 6400.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PROTUNE_SHARPNESS">
+      <entry value="0" name="GOPRO_PROTUNE_SHARPNESS_LOW">
+        <description>Low Sharpness.</description>
+      </entry>
+      <entry value="1" name="GOPRO_PROTUNE_SHARPNESS_MEDIUM">
+        <description>Medium Sharpness.</description>
+      </entry>
+      <entry value="2" name="GOPRO_PROTUNE_SHARPNESS_HIGH">
+        <description>High Sharpness.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_PROTUNE_EXPOSURE">
+      <entry value="0" name="GOPRO_PROTUNE_EXPOSURE_NEG_5_0">
+        <description>-5.0 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="1" name="GOPRO_PROTUNE_EXPOSURE_NEG_4_5">
+        <description>-4.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="2" name="GOPRO_PROTUNE_EXPOSURE_NEG_4_0">
+        <description>-4.0 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="3" name="GOPRO_PROTUNE_EXPOSURE_NEG_3_5">
+        <description>-3.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="4" name="GOPRO_PROTUNE_EXPOSURE_NEG_3_0">
+        <description>-3.0 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="5" name="GOPRO_PROTUNE_EXPOSURE_NEG_2_5">
+        <description>-2.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="6" name="GOPRO_PROTUNE_EXPOSURE_NEG_2_0">
+        <description>-2.0 EV.</description>
+      </entry>
+      <entry value="7" name="GOPRO_PROTUNE_EXPOSURE_NEG_1_5">
+        <description>-1.5 EV.</description>
+      </entry>
+      <entry value="8" name="GOPRO_PROTUNE_EXPOSURE_NEG_1_0">
+        <description>-1.0 EV.</description>
+      </entry>
+      <entry value="9" name="GOPRO_PROTUNE_EXPOSURE_NEG_0_5">
+        <description>-0.5 EV.</description>
+      </entry>
+      <entry value="10" name="GOPRO_PROTUNE_EXPOSURE_ZERO">
+        <description>0.0 EV.</description>
+      </entry>
+      <entry value="11" name="GOPRO_PROTUNE_EXPOSURE_POS_0_5">
+        <description>+0.5 EV.</description>
+      </entry>
+      <entry value="12" name="GOPRO_PROTUNE_EXPOSURE_POS_1_0">
+        <description>+1.0 EV.</description>
+      </entry>
+      <entry value="13" name="GOPRO_PROTUNE_EXPOSURE_POS_1_5">
+        <description>+1.5 EV.</description>
+      </entry>
+      <entry value="14" name="GOPRO_PROTUNE_EXPOSURE_POS_2_0">
+        <description>+2.0 EV.</description>
+      </entry>
+      <entry value="15" name="GOPRO_PROTUNE_EXPOSURE_POS_2_5">
+        <description>+2.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="16" name="GOPRO_PROTUNE_EXPOSURE_POS_3_0">
+        <description>+3.0 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="17" name="GOPRO_PROTUNE_EXPOSURE_POS_3_5">
+        <description>+3.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="18" name="GOPRO_PROTUNE_EXPOSURE_POS_4_0">
+        <description>+4.0 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="19" name="GOPRO_PROTUNE_EXPOSURE_POS_4_5">
+        <description>+4.5 EV (Hero 3+ Only).</description>
+      </entry>
+      <entry value="20" name="GOPRO_PROTUNE_EXPOSURE_POS_5_0">
+        <description>+5.0 EV (Hero 3+ Only).</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_CHARGING">
+      <entry value="0" name="GOPRO_CHARGING_DISABLED">
+        <description>Charging disabled.</description>
+      </entry>
+      <entry value="1" name="GOPRO_CHARGING_ENABLED">
+        <description>Charging enabled.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_MODEL">
+      <entry value="0" name="GOPRO_MODEL_UNKNOWN">
+        <description>Unknown gopro model.</description>
+      </entry>
+      <entry value="1" name="GOPRO_MODEL_HERO_3_PLUS_SILVER">
+        <description>Hero 3+ Silver (HeroBus not supported by GoPro).</description>
+      </entry>
+      <entry value="2" name="GOPRO_MODEL_HERO_3_PLUS_BLACK">
+        <description>Hero 3+ Black.</description>
+      </entry>
+      <entry value="3" name="GOPRO_MODEL_HERO_4_SILVER">
+        <description>Hero 4 Silver.</description>
+      </entry>
+      <entry value="4" name="GOPRO_MODEL_HERO_4_BLACK">
+        <description>Hero 4 Black.</description>
+      </entry>
+    </enum>
+    <enum name="GOPRO_BURST_RATE">
+      <entry value="0" name="GOPRO_BURST_RATE_3_IN_1_SECOND">
+        <description>3 Shots / 1 Second.</description>
+      </entry>
+      <entry value="1" name="GOPRO_BURST_RATE_5_IN_1_SECOND">
+        <description>5 Shots / 1 Second.</description>
+      </entry>
+      <entry value="2" name="GOPRO_BURST_RATE_10_IN_1_SECOND">
+        <description>10 Shots / 1 Second.</description>
+      </entry>
+      <entry value="3" name="GOPRO_BURST_RATE_10_IN_2_SECOND">
+        <description>10 Shots / 2 Second.</description>
+      </entry>
+      <entry value="4" name="GOPRO_BURST_RATE_10_IN_3_SECOND">
+        <description>10 Shots / 3 Second (Hero 4 Only).</description>
+      </entry>
+      <entry value="5" name="GOPRO_BURST_RATE_30_IN_1_SECOND">
+        <description>30 Shots / 1 Second.</description>
+      </entry>
+      <entry value="6" name="GOPRO_BURST_RATE_30_IN_2_SECOND">
+        <description>30 Shots / 2 Second.</description>
+      </entry>
+      <entry value="7" name="GOPRO_BURST_RATE_30_IN_3_SECOND">
+        <description>30 Shots / 3 Second.</description>
+      </entry>
+      <entry value="8" name="GOPRO_BURST_RATE_30_IN_6_SECOND">
+        <description>30 Shots / 6 Second.</description>
+      </entry>
+    </enum>
+    <!-- led control pattern enums (enumeration of specific patterns) -->
+    <enum name="LED_CONTROL_PATTERN">
+      <entry value="0" name="LED_CONTROL_PATTERN_OFF">
+        <description>LED patterns off (return control to regular vehicle control).</description>
+      </entry>
+      <entry value="1" name="LED_CONTROL_PATTERN_FIRMWAREUPDATE">
+        <description>LEDs show pattern during firmware update.</description>
+      </entry>
+      <entry value="255" name="LED_CONTROL_PATTERN_CUSTOM">
+        <description>Custom Pattern using custom bytes fields.</description>
+      </entry>
+    </enum>
+    <!-- EKF_STATUS_FLAGS - these values should be bit-and with the messages flags field to know if flag has been set -->
+    <enum name="EKF_STATUS_FLAGS">
+      <description>Flags in EKF_STATUS message.</description>
+      <entry value="1" name="EKF_ATTITUDE">
+        <description>Set if EKF's attitude estimate is good.</description>
+      </entry>
+      <entry value="2" name="EKF_VELOCITY_HORIZ">
+        <description>Set if EKF's horizontal velocity estimate is good.</description>
+      </entry>
+      <entry value="4" name="EKF_VELOCITY_VERT">
+        <description>Set if EKF's vertical velocity estimate is good.</description>
+      </entry>
+      <entry value="8" name="EKF_POS_HORIZ_REL">
+        <description>Set if EKF's horizontal position (relative) estimate is good.</description>
+      </entry>
+      <entry value="16" name="EKF_POS_HORIZ_ABS">
+        <description>Set if EKF's horizontal position (absolute) estimate is good.</description>
+      </entry>
+      <entry value="32" name="EKF_POS_VERT_ABS">
+        <description>Set if EKF's vertical position (absolute) estimate is good.</description>
+      </entry>
+      <entry value="64" name="EKF_POS_VERT_AGL">
+        <description>Set if EKF's vertical position (above ground) estimate is good.</description>
+      </entry>
+      <entry value="128" name="EKF_CONST_POS_MODE">
+        <description>EKF is in constant position mode and does not know it's absolute or relative position.</description>
+      </entry>
+      <entry value="256" name="EKF_PRED_POS_HORIZ_REL">
+        <description>Set if EKF's predicted horizontal position (relative) estimate is good.</description>
+      </entry>
+      <entry value="512" name="EKF_PRED_POS_HORIZ_ABS">
+        <description>Set if EKF's predicted horizontal position (absolute) estimate is good.</description>
+      </entry>
+    </enum>
+    <enum name="PID_TUNING_AXIS">
+      <entry value="1" name="PID_TUNING_ROLL"/>
+      <entry value="2" name="PID_TUNING_PITCH"/>
+      <entry value="3" name="PID_TUNING_YAW"/>
+      <entry value="4" name="PID_TUNING_ACCZ"/>
+      <entry value="5" name="PID_TUNING_STEER"/>
+      <entry value="6" name="PID_TUNING_LANDING"/>
+    </enum>
+    <enum name="MAG_CAL_STATUS">
+      <entry value="0" name="MAG_CAL_NOT_STARTED"/>
+      <entry value="1" name="MAG_CAL_WAITING_TO_START"/>
+      <entry value="2" name="MAG_CAL_RUNNING_STEP_ONE"/>
+      <entry value="3" name="MAG_CAL_RUNNING_STEP_TWO"/>
+      <entry value="4" name="MAG_CAL_SUCCESS"/>
+      <entry value="5" name="MAG_CAL_FAILED"/>
+      <entry value="6" name="MAG_CAL_BAD_ORIENTATION"/>
+    </enum>
+    <enum name="MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS">
+      <description>Special ACK block numbers control activation of dataflash log streaming.</description>
+      <!-- C uses signed integers for enumerations; these constants start at MAX_INT32_T and go down -->
+      <!-- 2^31-3 == 2147483645 -->
+      <entry value="2147483645" name="MAV_REMOTE_LOG_DATA_BLOCK_STOP">
+        <description>UAV to stop sending DataFlash blocks.</description>
+      </entry>
+      <!-- 2^31-2 == 2147483646 -->
+      <entry value="2147483646" name="MAV_REMOTE_LOG_DATA_BLOCK_START">
+        <description>UAV to start sending DataFlash blocks.</description>
+      </entry>
+      <!-- MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS_ENUM_END will be 2^31-1 == 2147483647 -->
+    </enum>
+    <enum name="MAV_REMOTE_LOG_DATA_BLOCK_STATUSES">
+      <description>Possible remote log data block statuses.</description>
+      <entry value="0" name="MAV_REMOTE_LOG_DATA_BLOCK_NACK">
+        <description>This block has NOT been received.</description>
+      </entry>
+      <entry value="1" name="MAV_REMOTE_LOG_DATA_BLOCK_ACK">
+        <description>This block has been received.</description>
+      </entry>
+    </enum>
+    <enum name="DEVICE_OP_BUSTYPE">
+      <description>Bus types for device operations.</description>
+      <entry value="0" name="DEVICE_OP_BUSTYPE_I2C">
+        <description>I2C Device operation.</description>
+      </entry>
+      <entry value="1" name="DEVICE_OP_BUSTYPE_SPI">
+        <description>SPI Device operation.</description>
+      </entry>
+    </enum>
+    <enum name="DEEPSTALL_STAGE">
+      <description>Deepstall flight stage.</description>
+      <entry value="0" name="DEEPSTALL_STAGE_FLY_TO_LANDING">
+        <description>Flying to the landing point.</description>
+      </entry>
+      <entry value="1" name="DEEPSTALL_STAGE_ESTIMATE_WIND">
+        <description>Building an estimate of the wind.</description>
+      </entry>
+      <entry value="2" name="DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT">
+        <description>Waiting to breakout of the loiter to fly the approach.</description>
+      </entry>
+      <entry value="3" name="DEEPSTALL_STAGE_FLY_TO_ARC">
+        <description>Flying to the first arc point to turn around to the landing point.</description>
+      </entry>
+      <entry value="4" name="DEEPSTALL_STAGE_ARC">
+        <description>Turning around back to the deepstall landing point.</description>
+      </entry>
+      <entry value="5" name="DEEPSTALL_STAGE_APPROACH">
+        <description>Approaching the landing point.</description>
+      </entry>
+      <entry value="6" name="DEEPSTALL_STAGE_LAND">
+        <description>Stalling and steering towards the land point.</description>
+      </entry>
+    </enum>
+    <enum name="PLANE_MODE">
+      <description>A mapping of plane flight modes for custom_mode field of heartbeat.</description>
+      <entry value="0" name="PLANE_MODE_MANUAL"/>
+      <entry value="1" name="PLANE_MODE_CIRCLE"/>
+      <entry value="2" name="PLANE_MODE_STABILIZE"/>
+      <entry value="3" name="PLANE_MODE_TRAINING"/>
+      <entry value="4" name="PLANE_MODE_ACRO"/>
+      <entry value="5" name="PLANE_MODE_FLY_BY_WIRE_A"/>
+      <entry value="6" name="PLANE_MODE_FLY_BY_WIRE_B"/>
+      <entry value="7" name="PLANE_MODE_CRUISE"/>
+      <entry value="8" name="PLANE_MODE_AUTOTUNE"/>
+      <entry value="10" name="PLANE_MODE_AUTO"/>
+      <entry value="11" name="PLANE_MODE_RTL"/>
+      <entry value="12" name="PLANE_MODE_LOITER"/>
+      <entry value="14" name="PLANE_MODE_AVOID_ADSB"/>
+      <entry value="15" name="PLANE_MODE_GUIDED"/>
+      <entry value="16" name="PLANE_MODE_INITIALIZING"/>
+      <entry value="17" name="PLANE_MODE_QSTABILIZE"/>
+      <entry value="18" name="PLANE_MODE_QHOVER"/>
+      <entry value="19" name="PLANE_MODE_QLOITER"/>
+      <entry value="20" name="PLANE_MODE_QLAND"/>
+      <entry value="21" name="PLANE_MODE_QRTL"/>
+      <entry value="22" name="PLANE_MODE_QAUTOTUNE"/>
+    </enum>
+    <enum name="COPTER_MODE">
+      <description>A mapping of copter flight modes for custom_mode field of heartbeat.</description>
+      <entry value="0" name="COPTER_MODE_STABILIZE"/>
+      <entry value="1" name="COPTER_MODE_ACRO"/>
+      <entry value="2" name="COPTER_MODE_ALT_HOLD"/>
+      <entry value="3" name="COPTER_MODE_AUTO"/>
+      <entry value="4" name="COPTER_MODE_GUIDED"/>
+      <entry value="5" name="COPTER_MODE_LOITER"/>
+      <entry value="6" name="COPTER_MODE_RTL"/>
+      <entry value="7" name="COPTER_MODE_CIRCLE"/>
+      <entry value="9" name="COPTER_MODE_LAND"/>
+      <entry value="11" name="COPTER_MODE_DRIFT"/>
+      <entry value="13" name="COPTER_MODE_SPORT"/>
+      <entry value="14" name="COPTER_MODE_FLIP"/>
+      <entry value="15" name="COPTER_MODE_AUTOTUNE"/>
+      <entry value="16" name="COPTER_MODE_POSHOLD"/>
+      <entry value="17" name="COPTER_MODE_BRAKE"/>
+      <entry value="18" name="COPTER_MODE_THROW"/>
+      <entry value="19" name="COPTER_MODE_AVOID_ADSB"/>
+      <entry value="20" name="COPTER_MODE_GUIDED_NOGPS"/>
+      <entry value="21" name="COPTER_MODE_SMART_RTL"/>
+    </enum>
+    <enum name="SUB_MODE">
+      <description>A mapping of sub flight modes for custom_mode field of heartbeat.</description>
+      <entry value="0" name="SUB_MODE_STABILIZE"/>
+      <entry value="1" name="SUB_MODE_ACRO"/>
+      <entry value="2" name="SUB_MODE_ALT_HOLD"/>
+      <entry value="3" name="SUB_MODE_AUTO"/>
+      <entry value="4" name="SUB_MODE_GUIDED"/>
+      <entry value="7" name="SUB_MODE_CIRCLE"/>
+      <entry value="9" name="SUB_MODE_SURFACE"/>
+      <entry value="16" name="SUB_MODE_POSHOLD"/>
+      <entry value="19" name="SUB_MODE_MANUAL"/>
+    </enum>
+    <enum name="ROVER_MODE">
+      <description>A mapping of rover flight modes for custom_mode field of heartbeat.</description>
+      <entry value="0" name="ROVER_MODE_MANUAL"/>
+      <entry value="1" name="ROVER_MODE_ACRO"/>
+      <entry value="3" name="ROVER_MODE_STEERING"/>
+      <entry value="4" name="ROVER_MODE_HOLD"/>
+      <entry value="5" name="ROVER_MODE_LOITER"/>
+      <entry value="10" name="ROVER_MODE_AUTO"/>
+      <entry value="11" name="ROVER_MODE_RTL"/>
+      <entry value="12" name="ROVER_MODE_SMART_RTL"/>
+      <entry value="15" name="ROVER_MODE_GUIDED"/>
+      <entry value="16" name="ROVER_MODE_INITIALIZING"/>
+    </enum>
+    <enum name="TRACKER_MODE">
+      <description>A mapping of antenna tracker flight modes for custom_mode field of heartbeat.</description>
+      <entry value="0" name="TRACKER_MODE_MANUAL"/>
+      <entry value="1" name="TRACKER_MODE_STOP"/>
+      <entry value="2" name="TRACKER_MODE_SCAN"/>
+      <entry value="3" name="TRACKER_MODE_SERVO_TEST"/>
+      <entry value="10" name="TRACKER_MODE_AUTO"/>
+      <entry value="16" name="TRACKER_MODE_INITIALIZING"/>
+    </enum>
+  </enums>
+  <messages>
+    <message id="150" name="SENSOR_OFFSETS">
+      <description>Offsets and calibrations values for hardware sensors. This makes it easier to debug the calibration process.</description>
+      <field type="int16_t" name="mag_ofs_x">Magnetometer X offset.</field>
+      <field type="int16_t" name="mag_ofs_y">Magnetometer Y offset.</field>
+      <field type="int16_t" name="mag_ofs_z">Magnetometer Z offset.</field>
+      <field type="float" name="mag_declination" units="rad">Magnetic declination.</field>
+      <field type="int32_t" name="raw_press">Raw pressure from barometer.</field>
+      <field type="int32_t" name="raw_temp">Raw temperature from barometer.</field>
+      <field type="float" name="gyro_cal_x">Gyro X calibration.</field>
+      <field type="float" name="gyro_cal_y">Gyro Y calibration.</field>
+      <field type="float" name="gyro_cal_z">Gyro Z calibration.</field>
+      <field type="float" name="accel_cal_x">Accel X calibration.</field>
+      <field type="float" name="accel_cal_y">Accel Y calibration.</field>
+      <field type="float" name="accel_cal_z">Accel Z calibration.</field>
+    </message>
+    <message id="151" name="SET_MAG_OFFSETS">
+      <deprecated since="2014-07" replaced_by="MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS"/>
+      <description>Set the magnetometer offsets</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="int16_t" name="mag_ofs_x">Magnetometer X offset.</field>
+      <field type="int16_t" name="mag_ofs_y">Magnetometer Y offset.</field>
+      <field type="int16_t" name="mag_ofs_z">Magnetometer Z offset.</field>
+    </message>
+    <message id="152" name="MEMINFO">
+      <description>State of APM memory.</description>
+      <field type="uint16_t" name="brkval">Heap top.</field>
+      <field type="uint16_t" name="freemem" units="bytes">Free memory.</field>
+      <extensions/>
+      <field type="uint32_t" name="freemem32" units="bytes">Free memory (32 bit).</field>
+    </message>
+    <message id="153" name="AP_ADC">
+      <description>Raw ADC output.</description>
+      <field type="uint16_t" name="adc1">ADC output 1.</field>
+      <field type="uint16_t" name="adc2">ADC output 2.</field>
+      <field type="uint16_t" name="adc3">ADC output 3.</field>
+      <field type="uint16_t" name="adc4">ADC output 4.</field>
+      <field type="uint16_t" name="adc5">ADC output 5.</field>
+      <field type="uint16_t" name="adc6">ADC output 6.</field>
+    </message>
+    <!-- Camera Controller Messages -->
+    <message id="154" name="DIGICAM_CONFIGURE">
+      <description>Configure on-board Camera Control System.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="mode">Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).</field>
+      <field type="uint16_t" name="shutter_speed">Divisor number //e.g. 1000 means 1/1000 (0 means ignore).</field>
+      <field type="uint8_t" name="aperture">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).</field>
+      <field type="uint8_t" name="iso">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).</field>
+      <field type="uint8_t" name="exposure_type">Exposure type enumeration from 1 to N (0 means ignore).</field>
+      <field type="uint8_t" name="command_id">Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.</field>
+      <field type="uint8_t" name="engine_cut_off" units="ds">Main engine cut-off time before camera trigger (0 means no cut-off).</field>
+      <field type="uint8_t" name="extra_param">Extra parameters enumeration (0 means ignore).</field>
+      <field type="float" name="extra_value">Correspondent value to given extra_param.</field>
+    </message>
+    <message id="155" name="DIGICAM_CONTROL">
+      <description>Control on-board Camera Control System to take shots.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="session">0: stop, 1: start or keep it up //Session control e.g. show/hide lens.</field>
+      <field type="uint8_t" name="zoom_pos">1 to N //Zoom's absolute position (0 means ignore).</field>
+      <field type="int8_t" name="zoom_step">-100 to 100 //Zooming step value to offset zoom from the current position.</field>
+      <field type="uint8_t" name="focus_lock">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.</field>
+      <field type="uint8_t" name="shot">0: ignore, 1: shot or start filming.</field>
+      <field type="uint8_t" name="command_id">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.</field>
+      <field type="uint8_t" name="extra_param">Extra parameters enumeration (0 means ignore).</field>
+      <field type="float" name="extra_value">Correspondent value to given extra_param.</field>
+    </message>
+    <!-- Camera Mount Messages -->
+    <message id="156" name="MOUNT_CONFIGURE">
+      <description>Message to configure a camera mount, directional antenna, etc.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="mount_mode" enum="MAV_MOUNT_MODE">Mount operating mode.</field>
+      <field type="uint8_t" name="stab_roll">(1 = yes, 0 = no).</field>
+      <field type="uint8_t" name="stab_pitch">(1 = yes, 0 = no).</field>
+      <field type="uint8_t" name="stab_yaw">(1 = yes, 0 = no).</field>
+    </message>
+    <message id="157" name="MOUNT_CONTROL">
+      <description>Message to control a camera mount, directional antenna, etc.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="int32_t" name="input_a">Pitch (centi-degrees) or lat (degE7), depending on mount mode.</field>
+      <field type="int32_t" name="input_b">Roll (centi-degrees) or lon (degE7) depending on mount mode.</field>
+      <field type="int32_t" name="input_c">Yaw (centi-degrees) or alt (cm) depending on mount mode.</field>
+      <field type="uint8_t" name="save_position">If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).</field>
+    </message>
+    <message id="158" name="MOUNT_STATUS">
+      <description>Message with some status from APM to GCS about camera or antenna mount.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="int32_t" name="pointing_a" units="cdeg">Pitch.</field>
+      <field type="int32_t" name="pointing_b" units="cdeg">Roll.</field>
+      <field type="int32_t" name="pointing_c" units="cdeg">Yaw.</field>
+    </message>
+    <!-- geo-fence messages -->
+    <message id="160" name="FENCE_POINT">
+      <description>A fence point. Used to set a point when from GCS -&gt; MAV. Also used to return a point from MAV -&gt; GCS.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="idx">Point index (first point is 1, 0 is for return point).</field>
+      <field type="uint8_t" name="count">Total number of points (for sanity checking).</field>
+      <field type="float" name="lat" units="deg">Latitude of point.</field>
+      <field type="float" name="lng" units="deg">Longitude of point.</field>
+    </message>
+    <message id="161" name="FENCE_FETCH_POINT">
+      <description>Request a current fence point from MAV.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="idx">Point index (first point is 1, 0 is for return point).</field>
+    </message>
+    <message id="162" name="FENCE_STATUS">
+      <description>Status of geo-fencing. Sent in extended status stream when fencing enabled.</description>
+      <field type="uint8_t" name="breach_status">Breach status (0 if currently inside fence, 1 if outside).</field>
+      <field type="uint16_t" name="breach_count">Number of fence breaches.</field>
+      <field type="uint8_t" name="breach_type" enum="FENCE_BREACH">Last breach type.</field>
+      <field type="uint32_t" name="breach_time" units="ms">Time (since boot) of last breach.</field>
+    </message>
+    <message id="163" name="AHRS">
+      <description>Status of DCM attitude estimator.</description>
+      <field type="float" name="omegaIx" units="rad/s">X gyro drift estimate.</field>
+      <field type="float" name="omegaIy" units="rad/s">Y gyro drift estimate.</field>
+      <field type="float" name="omegaIz" units="rad/s">Z gyro drift estimate.</field>
+      <field type="float" name="accel_weight">Average accel_weight.</field>
+      <field type="float" name="renorm_val">Average renormalisation value.</field>
+      <field type="float" name="error_rp">Average error_roll_pitch value.</field>
+      <field type="float" name="error_yaw">Average error_yaw value.</field>
+    </message>
+    <message id="164" name="SIMSTATE">
+      <description>Status of simulation environment, if used.</description>
+      <field type="float" name="roll" units="rad">Roll angle.</field>
+      <field type="float" name="pitch" units="rad">Pitch angle.</field>
+      <field type="float" name="yaw" units="rad">Yaw angle.</field>
+      <field type="float" name="xacc" units="m/s/s">X acceleration.</field>
+      <field type="float" name="yacc" units="m/s/s">Y acceleration.</field>
+      <field type="float" name="zacc" units="m/s/s">Z acceleration.</field>
+      <field type="float" name="xgyro" units="rad/s">Angular speed around X axis.</field>
+      <field type="float" name="ygyro" units="rad/s">Angular speed around Y axis.</field>
+      <field type="float" name="zgyro" units="rad/s">Angular speed around Z axis.</field>
+      <field type="int32_t" name="lat" units="degE7">Latitude.</field>
+      <field type="int32_t" name="lng" units="degE7">Longitude.</field>
+    </message>
+    <message id="165" name="HWSTATUS">
+      <description>Status of key hardware.</description>
+      <field type="uint16_t" name="Vcc" units="mV">Board voltage.</field>
+      <field type="uint8_t" name="I2Cerr">I2C error count.</field>
+    </message>
+    <message id="166" name="RADIO">
+      <description>Status generated by radio.</description>
+      <field type="uint8_t" name="rssi">Local signal strength.</field>
+      <field type="uint8_t" name="remrssi">Remote signal strength.</field>
+      <field type="uint8_t" name="txbuf" units="%">How full the tx buffer is.</field>
+      <field type="uint8_t" name="noise">Background noise level.</field>
+      <field type="uint8_t" name="remnoise">Remote background noise level.</field>
+      <field type="uint16_t" name="rxerrors">Receive errors.</field>
+      <field type="uint16_t" name="fixed">Count of error corrected packets.</field>
+    </message>
+    <!-- AP_Limits status -->
+    <message id="167" name="LIMITS_STATUS">
+      <description>Status of AP_Limits. Sent in extended status stream when AP_Limits is enabled.</description>
+      <field type="uint8_t" name="limits_state" enum="LIMITS_STATE">State of AP_Limits.</field>
+      <field type="uint32_t" name="last_trigger" units="ms">Time (since boot) of last breach.</field>
+      <field type="uint32_t" name="last_action" units="ms">Time (since boot) of last recovery action.</field>
+      <field type="uint32_t" name="last_recovery" units="ms">Time (since boot) of last successful recovery.</field>
+      <field type="uint32_t" name="last_clear" units="ms">Time (since boot) of last all-clear.</field>
+      <field type="uint16_t" name="breach_count">Number of fence breaches.</field>
+      <field type="uint8_t" name="mods_enabled" enum="LIMIT_MODULE" display="bitmask">AP_Limit_Module bitfield of enabled modules.</field>
+      <field type="uint8_t" name="mods_required" enum="LIMIT_MODULE" display="bitmask">AP_Limit_Module bitfield of required modules.</field>
+      <field type="uint8_t" name="mods_triggered" enum="LIMIT_MODULE" display="bitmask">AP_Limit_Module bitfield of triggered modules.</field>
+    </message>
+    <message id="168" name="WIND">
+      <description>Wind estimation.</description>
+      <field type="float" name="direction" units="deg">Wind direction (that wind is coming from).</field>
+      <field type="float" name="speed" units="m/s">Wind speed in ground plane.</field>
+      <field type="float" name="speed_z" units="m/s">Vertical wind speed.</field>
+    </message>
+    <message id="169" name="DATA16">
+      <description>Data packet, size 16.</description>
+      <field type="uint8_t" name="type">Data type.</field>
+      <field type="uint8_t" name="len" units="bytes">Data length.</field>
+      <field type="uint8_t[16]" name="data">Raw data.</field>
+    </message>
+    <message id="170" name="DATA32">
+      <description>Data packet, size 32.</description>
+      <field type="uint8_t" name="type">Data type.</field>
+      <field type="uint8_t" name="len" units="bytes">Data length.</field>
+      <field type="uint8_t[32]" name="data">Raw data.</field>
+    </message>
+    <message id="171" name="DATA64">
+      <description>Data packet, size 64.</description>
+      <field type="uint8_t" name="type">Data type.</field>
+      <field type="uint8_t" name="len" units="bytes">Data length.</field>
+      <field type="uint8_t[64]" name="data">Raw data.</field>
+    </message>
+    <message id="172" name="DATA96">
+      <description>Data packet, size 96.</description>
+      <field type="uint8_t" name="type">Data type.</field>
+      <field type="uint8_t" name="len" units="bytes">Data length.</field>
+      <field type="uint8_t[96]" name="data">Raw data.</field>
+    </message>
+    <message id="173" name="RANGEFINDER">
+      <description>Rangefinder reporting.</description>
+      <field type="float" name="distance" units="m">Distance.</field>
+      <field type="float" name="voltage" units="V">Raw voltage if available, zero otherwise.</field>
+    </message>
+    <message id="174" name="AIRSPEED_AUTOCAL">
+      <description>Airspeed auto-calibration.</description>
+      <field type="float" name="vx" units="m/s">GPS velocity north.</field>
+      <field type="float" name="vy" units="m/s">GPS velocity east.</field>
+      <field type="float" name="vz" units="m/s">GPS velocity down.</field>
+      <field type="float" name="diff_pressure" units="Pa">Differential pressure.</field>
+      <field type="float" name="EAS2TAS">Estimated to true airspeed ratio.</field>
+      <field type="float" name="ratio">Airspeed ratio.</field>
+      <field type="float" name="state_x">EKF state x.</field>
+      <field type="float" name="state_y">EKF state y.</field>
+      <field type="float" name="state_z">EKF state z.</field>
+      <field type="float" name="Pax">EKF Pax.</field>
+      <field type="float" name="Pby">EKF Pby.</field>
+      <field type="float" name="Pcz">EKF Pcz.</field>
+    </message>
+    <!-- Rally point messages -->
+    <message id="175" name="RALLY_POINT">
+      <description>A rally point. Used to set a point when from GCS -&gt; MAV. Also used to return a point from MAV -&gt; GCS.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="idx">Point index (first point is 0).</field>
+      <field type="uint8_t" name="count">Total number of points (for sanity checking).</field>
+      <field type="int32_t" name="lat" units="degE7">Latitude of point.</field>
+      <field type="int32_t" name="lng" units="degE7">Longitude of point.</field>
+      <field type="int16_t" name="alt" units="m">Transit / loiter altitude relative to home.</field>
+      <!-- Path planned landings are still in the future, but we want these fields ready: -->
+      <field type="int16_t" name="break_alt" units="m">Break altitude relative to home.</field>
+      <field type="uint16_t" name="land_dir" units="cdeg">Heading to aim for when landing.</field>
+      <field type="uint8_t" name="flags" enum="RALLY_FLAGS" display="bitmask">Configuration flags.</field>
+    </message>
+    <message id="176" name="RALLY_FETCH_POINT">
+      <description>Request a current rally point from MAV. MAV should respond with a RALLY_POINT message. MAV should not respond if the request is invalid.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="idx">Point index (first point is 0).</field>
+    </message>
+    <message id="177" name="COMPASSMOT_STATUS">
+      <description>Status of compassmot calibration.</description>
+      <field type="uint16_t" name="throttle" units="d%">Throttle.</field>
+      <field type="float" name="current" units="A">Current.</field>
+      <field type="uint16_t" name="interference" units="%">Interference.</field>
+      <field type="float" name="CompensationX">Motor Compensation X.</field>
+      <field type="float" name="CompensationY">Motor Compensation Y.</field>
+      <field type="float" name="CompensationZ">Motor Compensation Z.</field>
+    </message>
+    <!-- Coming soon <message name="RALLY_LAND_POINT" id="177"> <description>A rally landing point. An aircraft loitering at a rally point may choose one of these points to land at.</description> <field name="target_system" type="uint8_t">System ID.</field> <field name="target_component" type="uint8_t">Component ID.</field> <field name="idx" type="uint8_t">Point index (first point is 0).</field> <field name="count" type="uint8_t">Total number of points (for sanity checking).</field> <field name="lat" type="int32_t">Latitude of point.</field> <field name="lng" type="int32_t">Longitude of point.</field> <field name="alt" type="uint16_t">Ground AGL (usually 0).</field> </message> <message name="RALLY_LAND_FETCH_POINT" id="178"> <description>Request a current rally land point from MAV.</description> <field name="target_system" type="uint8_t">System ID.</field> <field name="target_component" type="uint8_t">Component ID.</field> <field name="idx" type="uint8_t">Point index (first point is 0).</field> </message> -->
+    <message id="178" name="AHRS2">
+      <description>Status of secondary AHRS filter if available.</description>
+      <field type="float" name="roll" units="rad">Roll angle.</field>
+      <field type="float" name="pitch" units="rad">Pitch angle.</field>
+      <field type="float" name="yaw" units="rad">Yaw angle.</field>
+      <field type="float" name="altitude" units="m">Altitude (MSL).</field>
+      <field type="int32_t" name="lat" units="degE7">Latitude.</field>
+      <field type="int32_t" name="lng" units="degE7">Longitude.</field>
+    </message>
+    <!-- camera event message from CCB to autopilot: for image trigger events but also things like heartbeat, error, low power, full card, etc -->
+    <message id="179" name="CAMERA_STATUS">
+      <description>Camera Event.</description>
+      <field type="uint64_t" name="time_usec" units="us">Image timestamp (since UNIX epoch, according to camera clock).</field>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <!-- support multiple concurrent vehicles -->
+      <field type="uint8_t" name="cam_idx">Camera ID.</field>
+      <!-- component ID, to support multiple cameras -->
+      <field type="uint16_t" name="img_idx">Image index.</field>
+      <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
+      <field type="uint8_t" name="event_id" enum="CAMERA_STATUS_TYPES">Event type.</field>
+      <field type="float" name="p1">Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).</field>
+      <field type="float" name="p2">Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).</field>
+      <field type="float" name="p3">Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).</field>
+      <field type="float" name="p4">Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).</field>
+    </message>
+    <!-- camera feedback message - can be originated from CCB (in response to a CAMERA_STATUS), or directly from the autopilot as part of a DO_DIGICAM_CONTROL-->
+    <message id="180" name="CAMERA_FEEDBACK">
+      <description>Camera Capture Feedback.</description>
+      <field type="uint64_t" name="time_usec" units="us">Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).</field>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <!-- support multiple concurrent vehicles -->
+      <field type="uint8_t" name="cam_idx">Camera ID.</field>
+      <!-- component ID, to support multiple cameras -->
+      <field type="uint16_t" name="img_idx">Image index.</field>
+      <!-- per camera image index, should be unique+sequential within a mission, preferably non-wrapping -->
+      <field type="int32_t" name="lat" units="degE7">Latitude.</field>
+      <field type="int32_t" name="lng" units="degE7">Longitude.</field>
+      <field type="float" name="alt_msl" units="m">Altitude (MSL).</field>
+      <field type="float" name="alt_rel" units="m">Altitude (Relative to HOME location).</field>
+      <field type="float" name="roll" units="deg">Camera Roll angle (earth frame, +-180).</field>
+      <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
+      <field type="float" name="pitch" units="deg">Camera Pitch angle (earth frame, +-180).</field>
+      <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
+      <field type="float" name="yaw" units="deg">Camera Yaw (earth frame, 0-360, true).</field>
+      <!-- initially only supporting fixed cameras, in future we'll need feedback messages from the gimbal so we can include that offset here -->
+      <field type="float" name="foc_len" units="mm">Focal Length.</field>
+      <!-- per-image to support zooms. Zero means fixed focal length or unknown. Should be true mm, not scaled to 35mm film equivalent -->
+      <field type="uint8_t" name="flags" enum="CAMERA_FEEDBACK_FLAGS">Feedback flags.</field>
+      <!-- future proofing -->
+      <extensions/>
+      <field type="uint16_t" name="completed_captures">Completed image captures.</field>
+    </message>
+    <message id="181" name="BATTERY2">
+      <deprecated since="2017-04" replaced_by="BATTERY_STATUS"/>
+      <description>2nd Battery status</description>
+      <field type="uint16_t" name="voltage" units="mV">Voltage.</field>
+      <field type="int16_t" name="current_battery" units="cA">Battery current, -1: autopilot does not measure the current.</field>
+    </message>
+    <message id="182" name="AHRS3">
+      <description>Status of third AHRS filter if available. This is for ANU research group (Ali and Sean).</description>
+      <field type="float" name="roll" units="rad">Roll angle.</field>
+      <field type="float" name="pitch" units="rad">Pitch angle.</field>
+      <field type="float" name="yaw" units="rad">Yaw angle.</field>
+      <field type="float" name="altitude" units="m">Altitude (MSL).</field>
+      <field type="int32_t" name="lat" units="degE7">Latitude.</field>
+      <field type="int32_t" name="lng" units="degE7">Longitude.</field>
+      <field type="float" name="v1">Test variable1.</field>
+      <field type="float" name="v2">Test variable2.</field>
+      <field type="float" name="v3">Test variable3.</field>
+      <field type="float" name="v4">Test variable4.</field>
+    </message>
+    <message id="183" name="AUTOPILOT_VERSION_REQUEST">
+      <description>Request the autopilot version from the system/component.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+    </message>
+    <!-- remote log messages -->
+    <message id="184" name="REMOTE_LOG_DATA_BLOCK">
+      <description>Send a block of log data to remote location.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint32_t" name="seqno" enum="MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS">Log data block sequence number.</field>
+      <field type="uint8_t[200]" name="data">Log data block.</field>
+    </message>
+    <message id="185" name="REMOTE_LOG_BLOCK_STATUS">
+      <description>Send Status of each log block that autopilot board might have sent.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint32_t" name="seqno">Log data block sequence number.</field>
+      <field type="uint8_t" name="status" enum="MAV_REMOTE_LOG_DATA_BLOCK_STATUSES">Log data block status.</field>
+    </message>
+    <message id="186" name="LED_CONTROL">
+      <description>Control vehicle LEDs.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="instance">Instance (LED instance to control or 255 for all LEDs).</field>
+      <field type="uint8_t" name="pattern">Pattern (see LED_PATTERN_ENUM).</field>
+      <field type="uint8_t" name="custom_len">Custom Byte Length.</field>
+      <field type="uint8_t[24]" name="custom_bytes">Custom Bytes.</field>
+    </message>
+    <message id="191" name="MAG_CAL_PROGRESS">
+      <description>Reports progress of compass calibration.</description>
+      <field type="uint8_t" name="compass_id">Compass being calibrated.</field>
+      <field type="uint8_t" name="cal_mask" display="bitmask">Bitmask of compasses being calibrated.</field>
+      <field type="uint8_t" name="cal_status" enum="MAG_CAL_STATUS">Calibration Status.</field>
+      <field type="uint8_t" name="attempt">Attempt number.</field>
+      <field type="uint8_t" name="completion_pct" units="%">Completion percentage.</field>
+      <field type="uint8_t[10]" name="completion_mask">Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).</field>
+      <field type="float" name="direction_x">Body frame direction vector for display.</field>
+      <field type="float" name="direction_y">Body frame direction vector for display.</field>
+      <field type="float" name="direction_z">Body frame direction vector for display.</field>
+    </message>
+    <message id="192" name="MAG_CAL_REPORT">
+      <description>Reports results of completed compass calibration. Sent until MAG_CAL_ACK received.</description>
+      <field type="uint8_t" name="compass_id">Compass being calibrated.</field>
+      <field type="uint8_t" name="cal_mask" display="bitmask">Bitmask of compasses being calibrated.</field>
+      <field type="uint8_t" name="cal_status" enum="MAG_CAL_STATUS">Calibration Status.</field>
+      <field type="uint8_t" name="autosaved">0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.</field>
+      <field type="float" name="fitness" units="mgauss">RMS milligauss residuals.</field>
+      <field type="float" name="ofs_x">X offset.</field>
+      <field type="float" name="ofs_y">Y offset.</field>
+      <field type="float" name="ofs_z">Z offset.</field>
+      <field type="float" name="diag_x">X diagonal (matrix 11).</field>
+      <field type="float" name="diag_y">Y diagonal (matrix 22).</field>
+      <field type="float" name="diag_z">Z diagonal (matrix 33).</field>
+      <field type="float" name="offdiag_x">X off-diagonal (matrix 12 and 21).</field>
+      <field type="float" name="offdiag_y">Y off-diagonal (matrix 13 and 31).</field>
+      <field type="float" name="offdiag_z">Z off-diagonal (matrix 32 and 23).</field>
+      <extensions/>
+      <field type="float" name="orientation_confidence">Confidence in orientation (higher is better).</field>
+      <field type="uint8_t" name="old_orientation" enum="MAV_SENSOR_ORIENTATION">orientation before calibration.</field>
+      <field type="uint8_t" name="new_orientation" enum="MAV_SENSOR_ORIENTATION">orientation after calibration.</field>
+    </message>
+    <!-- EKF status message from autopilot to GCS. -->
+    <message id="193" name="EKF_STATUS_REPORT">
+      <description>EKF Status message including flags and variances.</description>
+      <field type="uint16_t" name="flags" enum="EKF_STATUS_FLAGS">Flags.</field>
+      <!-- supported flags see EKF_STATUS_FLAGS enum -->
+      <field type="float" name="velocity_variance">Velocity variance.</field>
+      <!-- below 0.5 is good, 0.5~0.79 is warning, 0.8 or higher is bad -->
+      <field type="float" name="pos_horiz_variance">Horizontal Position variance.</field>
+      <field type="float" name="pos_vert_variance">Vertical Position variance.</field>
+      <field type="float" name="compass_variance">Compass variance.</field>
+      <field type="float" name="terrain_alt_variance">Terrain Altitude variance.</field>
+      <extensions/>
+      <field type="float" name="airspeed_variance">Airspeed variance.</field>
+    </message>
+    <!-- realtime PID tuning message -->
+    <message id="194" name="PID_TUNING">
+      <description>PID tuning information.</description>
+      <field type="uint8_t" name="axis" enum="PID_TUNING_AXIS">Axis.</field>
+      <field type="float" name="desired" units="deg/s">Desired rate.</field>
+      <field type="float" name="achieved" units="deg/s">Achieved rate.</field>
+      <field type="float" name="FF">FF component.</field>
+      <field type="float" name="P">P component.</field>
+      <field type="float" name="I">I component.</field>
+      <field type="float" name="D">D component.</field>
+    </message>
+    <message id="195" name="DEEPSTALL">
+      <description>Deepstall path planning.</description>
+      <field type="int32_t" name="landing_lat" units="degE7">Landing latitude.</field>
+      <field type="int32_t" name="landing_lon" units="degE7">Landing longitude.</field>
+      <field type="int32_t" name="path_lat" units="degE7">Final heading start point, latitude.</field>
+      <field type="int32_t" name="path_lon" units="degE7">Final heading start point, longitude.</field>
+      <field type="int32_t" name="arc_entry_lat" units="degE7">Arc entry point, latitude.</field>
+      <field type="int32_t" name="arc_entry_lon" units="degE7">Arc entry point, longitude.</field>
+      <field type="float" name="altitude" units="m">Altitude.</field>
+      <field type="float" name="expected_travel_distance" units="m">Distance the aircraft expects to travel during the deepstall.</field>
+      <field type="float" name="cross_track_error" units="m">Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).</field>
+      <field type="uint8_t" name="stage" enum="DEEPSTALL_STAGE">Deepstall stage.</field>
+    </message>
+    <message id="200" name="GIMBAL_REPORT">
+      <description>3 axis gimbal measurements.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="float" name="delta_time" units="s">Time since last update.</field>
+      <field type="float" name="delta_angle_x" units="rad">Delta angle X.</field>
+      <field type="float" name="delta_angle_y" units="rad">Delta angle Y.</field>
+      <field type="float" name="delta_angle_z" units="rad">Delta angle X.</field>
+      <field type="float" name="delta_velocity_x" units="m/s">Delta velocity X.</field>
+      <field type="float" name="delta_velocity_y" units="m/s">Delta velocity Y.</field>
+      <field type="float" name="delta_velocity_z" units="m/s">Delta velocity Z.</field>
+      <field type="float" name="joint_roll" units="rad">Joint ROLL.</field>
+      <field type="float" name="joint_el" units="rad">Joint EL.</field>
+      <field type="float" name="joint_az" units="rad">Joint AZ.</field>
+    </message>
+    <message id="201" name="GIMBAL_CONTROL">
+      <description>Control message for rate gimbal.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="float" name="demanded_rate_x" units="rad/s">Demanded angular rate X.</field>
+      <field type="float" name="demanded_rate_y" units="rad/s">Demanded angular rate Y.</field>
+      <field type="float" name="demanded_rate_z" units="rad/s">Demanded angular rate Z.</field>
+    </message>
+    <message id="214" name="GIMBAL_TORQUE_CMD_REPORT">
+      <description>100 Hz gimbal torque command telemetry.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="int16_t" name="rl_torque_cmd">Roll Torque Command.</field>
+      <field type="int16_t" name="el_torque_cmd">Elevation Torque Command.</field>
+      <field type="int16_t" name="az_torque_cmd">Azimuth Torque Command.</field>
+    </message>
+    <!-- GoPro Messages -->
+    <message id="215" name="GOPRO_HEARTBEAT">
+      <description>Heartbeat from a HeroBus attached GoPro.</description>
+      <field type="uint8_t" name="status" enum="GOPRO_HEARTBEAT_STATUS">Status.</field>
+      <field type="uint8_t" name="capture_mode" enum="GOPRO_CAPTURE_MODE">Current capture mode.</field>
+      <field type="uint8_t" name="flags" enum="GOPRO_HEARTBEAT_FLAGS" display="bitmask">Additional status bits.</field>
+      <!-- see GOPRO_HEARTBEAT_FLAGS -->
+    </message>
+    <message id="216" name="GOPRO_GET_REQUEST">
+      <description>Request a GOPRO_COMMAND response from the GoPro.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="cmd_id" enum="GOPRO_COMMAND">Command ID.</field>
+    </message>
+    <message id="217" name="GOPRO_GET_RESPONSE">
+      <description>Response from a GOPRO_COMMAND get request.</description>
+      <field type="uint8_t" name="cmd_id" enum="GOPRO_COMMAND">Command ID.</field>
+      <field type="uint8_t" name="status" enum="GOPRO_REQUEST_STATUS">Status.</field>
+      <field type="uint8_t[4]" name="value">Value.</field>
+    </message>
+    <message id="218" name="GOPRO_SET_REQUEST">
+      <description>Request to set a GOPRO_COMMAND with a desired.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint8_t" name="cmd_id" enum="GOPRO_COMMAND">Command ID.</field>
+      <field type="uint8_t[4]" name="value">Value.</field>
+    </message>
+    <message id="219" name="GOPRO_SET_RESPONSE">
+      <description>Response from a GOPRO_COMMAND set request.</description>
+      <field type="uint8_t" name="cmd_id" enum="GOPRO_COMMAND">Command ID.</field>
+      <field type="uint8_t" name="status" enum="GOPRO_REQUEST_STATUS">Status.</field>
+    </message>
+    <!-- 219 to 224 RESERVED for more GOPRO-->
+    <message id="226" name="RPM">
+      <description>RPM sensor output.</description>
+      <field type="float" name="rpm1">RPM Sensor1.</field>
+      <field type="float" name="rpm2">RPM Sensor2.</field>
+    </message>
+	<message id="228" name="HV_REG_GET">
+	  <description>high voltage get reg data.</description>
+	  <field type="uint8_t" name="aim">size.</field>
+	  <field type="int32_t[3]" name="data">code.</field>
+	</message>
+    <message id="229" name="ROV_STATE_MONITORING">
+      <description>The upper computer monitors the APM status.</description>
+      <field type="int16_t" name="floodlight">floodlight PWM.</field>
+      <field type="int8_t" name="pressure_level">Pressure level.</field>
+      <field type="float" name="low_voltage">Low voltage.</field>
+      <field type="float" name="high_voltage">high voltage.</field>
+      <field type="float" name="deep">Depth of water.</field>
+      <field type="float" name="temp">Cabin temperature.</field>
+      <field type="uint16_t" name="motor_block_flag">motor block flag.</field>
+      <field type="uint16_t" name="forward">motor forward direction.</field>
+      <field type="uint16_t" name="turn">Motor turning direction.</field>
+      <field type="uint16_t" name="hvMotorMod">HV Motor Mod.</field>
+      <field type="uint16_t[8]" name="motor_twine_flag">motors twine flag.</field>
+      <field type="uint16_t[6]" name="motor_power">motors twine flag.</field>
+    </message>
+	<message id="235" name="MOTOR_SPEED">
+	  <description>motor speed communication.</description>
+	  <field type="uint8_t" name="motorTest">Motor Test status.</field>
+	  <field type="int16_t" name="Ltrack">left track motor.</field>
+	  <field type="int16_t" name="Rtrack">right track motor.</field>
+	  <field type="float" name="motor1">Motor1 speed.</field>
+	  <field type="float" name="motor2">Motor2 speed.</field>
+	  <field type="float" name="motor3">Motor3 speed.</field>
+	  <field type="float" name="motor4">Motor4 speed.</field>
+	  <field type="float" name="motor5">Motor5 speed.</field>
+	  <field type="float" name="motor6">Motor6 speed.</field>
+	  <field type="float" name="motor7">Motor7 speed.</field>
+	  <field type="float" name="motor8">Motor8 speed.</field>
+	</message>
+	<message id="236" name="ROV_CONTROL">
+	  <description>ROV control.</description>
+	  <field type="int8_t" name="USBL_flag">USBL open flag.</field>
+	  <field type="uint16_t" name="floodlight">floodlight PWM.</field>
+	  <field type="uint16_t" name="track_limit">track max speed limit.</field>
+	</message>
+	<message id="237" name="SET_SLAVE_PARAMETER">
+	  <description>float set: number flag XX1 XX2 XX3 XX4.YY = XXXXXX.YY.</description>
+	  <field type="uint8_t" name="number">number.</field>
+	  <field type="uint8_t" name="flag">flag.</field>
+	  <field type="uint8_t" name="XX1">Integral1.</field>
+	  <field type="uint8_t" name="XX2">Integral2.</field>
+	  <field type="uint8_t" name="XX3">Integral3.</field>
+	  <field type="uint8_t" name="XX4">Integral4.</field>
+	  <field type="uint8_t" name="YY">Float.</field>
+	</message>
+      <message id="238" name="ROTATION_MATRIX_ARRAY">
+      <description>Rotation matrix array.</description>
+      <field type="float" name="a11">a11.</field>
+      <field type="float" name="a12">a12.</field>
+      <field type="float" name="a13">a13.</field>
+      <field type="float" name="a21">a21.</field>
+      <field type="float" name="a22">a22.</field>
+      <field type="float" name="a23">a23.</field>
+      <field type="float" name="a31">a31.</field>
+      <field type="float" name="a32">a32.</field>
+      <field type="float" name="a33">a33.</field>
+    </message>
+	<message id="239" name="HV_REG_SET">
+	  <description>High voltage electric regulation parameter setting.</description>
+	  <field type="uint8_t" name="aim">size.</field>
+	  <field type="uint8_t" name="code">code.</field>
+	  <field type="uint8_t[13]" name="data">arry.</field>
+	</message>
+	<message id="240" name="SET_N2_PARAMETER">
+      <description>Monitoring motor speed feedback.</description>
+      <field type="float" name="trackP">trackP.</field>
+      <field type="float" name="trackI">trackI.</field>
+      <field type="float" name="trackD">trackD.</field>
+      <field type="float" name="brushP">brushP.</field>
+      <field type="float" name="brushI">brushI.</field>
+      <field type="float" name="brushD">brushD.</field>
+    </message>
+    <!-- ardupilot specific mavlink2 messages starting at 11000-->
+    <message id="11000" name="DEVICE_OP_READ">
+      <description>Read registers for a device.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint32_t" name="request_id">Request ID - copied to reply.</field>
+      <field type="uint8_t" name="bustype" enum="DEVICE_OP_BUSTYPE">The bus type.</field>
+      <field type="uint8_t" name="bus">Bus number.</field>
+      <field type="uint8_t" name="address">Bus address.</field>
+      <field type="char[40]" name="busname">Name of device on bus (for SPI).</field>
+      <field type="uint8_t" name="regstart">First register to read.</field>
+      <field type="uint8_t" name="count">Count of registers to read.</field>
+    </message>
+    <message id="11001" name="DEVICE_OP_READ_REPLY">
+      <description>Read registers reply.</description>
+      <field type="uint32_t" name="request_id">Request ID - copied from request.</field>
+      <field type="uint8_t" name="result">0 for success, anything else is failure code.</field>
+      <field type="uint8_t" name="regstart">Starting register.</field>
+      <field type="uint8_t" name="count">Count of bytes read.</field>
+      <field type="uint8_t[128]" name="data">Reply data.</field>
+    </message>
+    <message id="11002" name="DEVICE_OP_WRITE">
+      <description>Write registers for a device.</description>
+      <field type="uint8_t" name="target_system">System ID.</field>
+      <field type="uint8_t" name="target_component">Component ID.</field>
+      <field type="uint32_t" name="request_id">Request ID - copied to reply.</field>
+      <field type="uint8_t" name="bustype" enum="DEVICE_OP_BUSTYPE">The bus type.</field>
+      <field type="uint8_t" name="bus">Bus number.</field>
+      <field type="uint8_t" name="address">Bus address.</field>
+      <field type="char[40]" name="busname">Name of device on bus (for SPI).</field>
+      <field type="uint8_t" name="regstart">First register to write.</field>
+      <field type="uint8_t" name="count">Count of registers to write.</field>
+      <field type="uint8_t[128]" name="data">Write data.</field>
+    </message>
+    <message id="11003" name="DEVICE_OP_WRITE_REPLY">
+      <description>Write registers reply.</description>
+      <field type="uint32_t" name="request_id">Request ID - copied from request.</field>
+      <field type="uint8_t" name="result">0 for success, anything else is failure code.</field>
+    </message>
+    <!-- realtime Adaptive Controller tuning message -->
+    <message id="11010" name="ADAP_TUNING">
+      <description>Adaptive Controller tuning information.</description>
+      <field type="uint8_t" name="axis" enum="PID_TUNING_AXIS">Axis.</field>
+      <field type="float" name="desired" units="deg/s">Desired rate.</field>
+      <field type="float" name="achieved" units="deg/s">Achieved rate.</field>
+      <field type="float" name="error">Error between model and vehicle.</field>
+      <field type="float" name="theta">Theta estimated state predictor.</field>
+      <field type="float" name="omega">Omega estimated state predictor.</field>
+      <field type="float" name="sigma">Sigma estimated state predictor.</field>
+      <field type="float" name="theta_dot">Theta derivative.</field>
+      <field type="float" name="omega_dot">Omega derivative.</field>
+      <field type="float" name="sigma_dot">Sigma derivative.</field>
+      <field type="float" name="f">Projection operator value.</field>
+      <field type="float" name="f_dot">Projection operator derivative.</field>
+      <field type="float" name="u">u adaptive controlled output command.</field>
+    </message>
+    <!-- camera vision based attitude and position delta message -->
+    <message id="11011" name="VISION_POSITION_DELTA">
+      <description>Camera vision based attitude and position deltas.</description>
+      <field name="time_usec" type="uint64_t" units="us">Timestamp (synced to UNIX time or since system boot).</field>
+      <field name="time_delta_usec" type="uint64_t" units="us">Time since the last reported camera frame.</field>
+      <field type="float[3]" name="angle_delta">Defines a rotation vector in body frame that rotates the vehicle from the previous to the current orientation.</field>
+      <field type="float[3]" name="position_delta" units="m">Change in position from previous to current frame rotated into body frame (0=forward, 1=right, 2=down).</field>
+      <field type="float" name="confidence" units="%">Normalised confidence value from 0 to 100.</field>
+    </message>
+    <!-- Angle of Attack and Side Slip Angle message -->
+    <message id="11020" name="AOA_SSA">
+      <description>Angle of Attack and Side Slip Angle.</description>
+      <field type="uint64_t" name="time_usec" units="us">Timestamp (since boot or Unix epoch).</field>
+      <field name="AOA" type="float" units="deg">Angle of Attack.</field>
+      <field name="SSA" type="float" units="deg">Side Slip Angle.</field>
+    </message>
+    <message id="11030" name="ESC_TELEMETRY_1_TO_4">
+      <description>ESC Telemetry Data for ESCs 1 to 4, matching data sent by BLHeli ESCs.</description>
+      <field type="uint8_t[4]" name="temperature" units="degC">Temperature.</field>
+      <field type="uint16_t[4]" name="voltage" units="cV">Voltage.</field>
+      <field type="uint16_t[4]" name="current" units="cA">Current.</field>
+      <field type="uint16_t[4]" name="totalcurrent" units="mAh">Total current.</field>
+      <field type="uint16_t[4]" name="rpm" units="rpm">RPM (eRPM).</field>
+      <field type="uint16_t[4]" name="count">count of telemetry packets received (wraps at 65535).</field>
+    </message>
+    <message id="11031" name="ESC_TELEMETRY_5_TO_8">
+      <description>ESC Telemetry Data for ESCs 5 to 8, matching data sent by BLHeli ESCs.</description>
+      <field type="uint8_t[4]" name="temperature" units="degC">Temperature.</field>
+      <field type="uint16_t[4]" name="voltage" units="cV">Voltage.</field>
+      <field type="uint16_t[4]" name="current" units="cA">Current.</field>
+      <field type="uint16_t[4]" name="totalcurrent" units="mAh">Total current.</field>
+      <field type="uint16_t[4]" name="rpm" units="rpm">RPM (eRPM).</field>
+      <field type="uint16_t[4]" name="count">count of telemetry packets received (wraps at 65535).</field>
+    </message>
+    <message id="11032" name="ESC_TELEMETRY_9_TO_12">
+      <description>ESC Telemetry Data for ESCs 9 to 12, matching data sent by BLHeli ESCs.</description>
+      <field type="uint8_t[4]" name="temperature" units="degC">Temperature.</field>
+      <field type="uint16_t[4]" name="voltage" units="cV">Voltage.</field>
+      <field type="uint16_t[4]" name="current" units="cA">Current.</field>
+      <field type="uint16_t[4]" name="totalcurrent" units="mAh">Total current.</field>
+      <field type="uint16_t[4]" name="rpm" units="rpm">RPM (eRPM).</field>
+      <field type="uint16_t[4]" name="count">count of telemetry packets received (wraps at 65535).</field>
+    </message>
+  </messages>
+</mavlink>

+ 8 - 1
modules/mavlink/message_definitions/v1.0/ardupilotmega.xml

@@ -1500,6 +1500,11 @@
       <description>RPM sensor output.</description>
       <field type="float" name="rpm1">RPM Sensor1.</field>
       <field type="float" name="rpm2">RPM Sensor2.</field>
+    </message>
+      <message id="227" name="ROV_MOTOR_TEMP">
+      <description>motor temperature.</description>
+      <field type="int16_t[2]" name="track_temperature">motors twine flag.</field>
+      <field type="int16_t[8]" name="motor_temperature">motors twine flag.</field>
     </message>
 	<message id="228" name="HV_REG_GET">
 	  <description>high voltage get reg data.</description>
@@ -1518,8 +1523,10 @@
       <field type="uint16_t" name="forward">motor forward direction.</field>
       <field type="uint16_t" name="turn">Motor turning direction.</field>
       <field type="uint16_t" name="hvMotorMod">HV Motor Mod.</field>
+      <field type="uint16_t[2]" name="track_fault_flag">track twine flag.</field>
       <field type="uint16_t[8]" name="motor_twine_flag">motors twine flag.</field>
-      <field type="uint16_t[6]" name="motor_power">motors twine flag.</field>
+      <field type="int16_t[2]" name="track_power">track power.</field>
+      <field type="int16_t[8]" name="motor_power">motors power.</field>
     </message>
 	<message id="235" name="MOTOR_SPEED">
 	  <description>motor speed communication.</description>