How to use the C language library to upload landing routes and tasks to an airplane

I have debugged most of the communication between STM32 and the aircraft using the C language library. Including reading status information, reading and writing parameters, and downloading tasks.
However, the upload task section still failed to debug.
The problem is:

mavlink_msg_mission_count_pack(0xa8, 0XBE, &msg,1, 0,4, MAV_MISSION_TYPE_MISSION, 0);
l = mavlink_msg_to_send_buffer(sendda,&msg);
HAL_UART_Transmit(&huart2, sendda, l, 100);

After sending the Mission-COUNT packet, the aircraft does not return a Mission-QUEST-INT response.

I sent the Mission-COUNT packet in the order of the pictures, and then checked every 250MS to see if there was any data in the Mission-QUEST-INT, but it never had any data. Is there an error in the parameters in my mavlink_masg_comssion_comnt_cack package?
Compared to uploading tasks, downloading tasks are easier to debug and pass. Here is the program for downloading tasks.

if(0)//下载任务序列
		{
			neicun[0] = 0;//清除标志位
			cpuzhizhen[0] = 0;
			mavlink_msg_mission_request_list_pack(0xa8, 0XBE, &msg,1, 0, 0);//获取任务航点数
			l = mavlink_msg_to_send_buffer(sendda,&msg);
			HAL_UART_Transmit(&huart2, sendda, l, 100);
			for(int i = 0; i < 5; i++)
			{
				cpuzhizhen[0] = 1;
				delayms(250);
				if(neicun[0] == 1)//如果收到响应
				{
					cpuzhizhen[0] = 2;
					neicun[0] = 0;
					//cpuzhizhen[3] = neicun[1];
					for(int i2 = 0; i2 < neicun[1] ; i2++)//进入读任务序列
					{
						//cpuzhizhen[0] = 3;
						neicun[2] = 0;
						neicun[100] = i2;
						mavlink_msg_mission_request_int_pack(0xa8, 0XBE, &msg,1, 0, i2,MAV_MISSION_TYPE_MISSION);
						l = mavlink_msg_to_send_buffer(sendda,&msg);
						HAL_UART_Transmit(&huart2, sendda, l, 100);
						for(int i3 = 0; i3 < 5; i3++)
						{
							//cpuzhizhen[0] = 4;
							delayms(250);
							if(neicun[2] == 1)//如果收到响应
							{
								cpuzhizhen[1] = neicun[101];
								cpuzhizhen[2] = neicun[102];
								//cpuzhizhen[3] = neicun[103];
								cpuzhizhen[0] = 5;
								neicun[2]= 0;
								break;
							}
						}
						if(neicun[2] == 1)
						{
							cpuzhizhen[0] = 6;
							break;
						}

					}
					mavlink_msg_mission_ack_pack(0xa8, 0XBE, &msg, 1, 0, 0, MAV_MISSION_TYPE_MISSION, 0);
					l = mavlink_msg_to_send_buffer(sendda,&msg);
					HAL_UART_Transmit(&huart2, sendda, l, 100);
				}
			}
		}

				case MAVLINK_MSG_ID_MISSION_COUNT://任务数量
					{
						neicun[1] = mavlink_msg_mission_count_get_count(&msgin);
						//cpuzhizhen[1] = neicun[1];
						neicun[0] = 1;//响应标志位
						//cpuzhizhen[2]  ++;
						break;
					}
				case MAVLINK_MSG_ID_MISSION_CURRENT://任务数量
				{
					//cpuzhizhen[1] = mavlink_msg_mission_current_get_total(&msgin);//
					//cpuzhizhen[2]  ++;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_REQUEST_INT://飞机请求任务
				{
					neicun[10] = 1;
					neicun[12] = mavlink_msg_mission_request_int_get_seq(&msgin);
					//cpuzhizhen[1] = mavlink_msg_mission_request_int_get_mission_type(&msgin);
					//cpuzhizhen[2]  ++;
					//neicun[0] = 1;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_ITEM_INT://飞机请求任务
				{
					neicun[101 + neicun[ 100 ]] = mavlink_msg_mission_item_int_get_z(&msgin);
					//cpuzhizhen[1] = mavlink_msg_mission_item_int_get_seq(&msgin);
					neicun[2] = 1;
					//cpuzhizhen[2]++;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_ACK://飞机接收任务结束的指令ACK
				{
					//neicun[2] = 2;
					//cpuzhizhen[1] = mavlink_msg_mission_item_int_get_seq(&msgin);
					//cpuzhizhen[2]++;
					break;
				}

When I wrote a program to capture data packets, I found that the instruction returned by the plane was a replaced instruction, and there was no clear explanation on MAVLINK’s official website. Is the latest firmware of AP still using the discarded instruction?
No wonder I am unable to read the MAVLINK_SSG-ID_ISSION-REQUEST-INT command consistently, instead it should be MAVLINK_SSG-ID_ISSION-REQUEST



Here is an example of my writing task, please don’t take the wrong path

Because I am using the rtfreeos system, the processing of data sent and received through the serial port is separate


if(1)//写入任务
		{
			neicun[10] = 0;//清除标志位
			cpuzhizhen[0] = 0;
			mavlink_msg_mission_count_pack(0xa8, 0XBE, &msg,
									   1, 1,4, MAV_MISSION_TYPE_MISSION, 0);
			l = mavlink_msg_to_send_buffer(sendda,&msg);
			HAL_UART_Transmit(&huart2, sendda, l, 100);
			for(int i = 0; i < 5; i++)//进入等待程序
			{
				cpuzhizhen[0] = 1;
				delayms(250);
				if(neicun[10] == 1)
				{
					for(int i2 = 0; i2 < 4 ; i2++)//进入写任务序列
					{
						cpuzhizhen[0] = 2;
						neicun[10] = 0;
						neicun[12] = 0;
						mavlink_msg_mission_item_int_pack(0xa8, 0XBE, &msg,
										1, 0, neicun[13],
										MAV_FRAME_GLOBAL, MAV_CMD_NAV_WAYPOINT, 0, 1,
										0, 0, 0, 0, 0x12178EE1+i2*1000000, 0x478B23B3,
										1234, MAV_MISSION_TYPE_MISSION);

						l = mavlink_msg_to_send_buffer(sendda,&msg);
						HAL_UART_Transmit(&huart2, sendda, l, 100);
						for(int i3 = 0; i3 < 5 ; i3++)//进入写任务序列
						{
							cpuzhizhen[0] = 3;
							delayms(250);
							if(neicun[10] == 1)
							{
								neicun[10] = 0;
								cpuzhizhen[1] ++;
								cpuzhizhen[0] = 5;
							}
							if(neicun[12] == 1)
							{
								neicun[12] = 0;
								cpuzhizhen[0] = 6;
								break;
							}
						}
					}
				}
			}
		}


	while(1)
	{
		//delayms(1);//已经最低优先级

 		if(jieshou1changdu > 0)
		{
			jieshou1changdu = processArray(jieshou1, jieshou1changdu, &byte) ;

			if (mavlink_parse_char(chan, byte, &msgin, &status))
			{

				switch(msgin.msgid) {
				case MAVLINK_MSG_ID_ATTITUDE:
					{
					  // Get just one field from payload
						//cpuzhizhen[0] = mavlink_msg_attitude_get_roll(&msgin) * 180/3.14+10000;

						jiedian[55] = (~jiedian[55])&1;
						break;
					}
				case MAVLINK_MSG_ID_PARAM_VALUE://读取返回的参数,需要先读取ID,16位的数据,不足16用0占位
					{
					  // Get just one field from payload
						len = mavlink_msg_param_set_get_param_id(&msgin, pr);
//						cpuzhizhen[1] = mavlink_msg_param_set_get_param_value(&msgin);
//						cpuzhizhen[2]  ++;
						break;
					}
				case MAVLINK_MSG_ID_MISSION_COUNT://任务数量
					{
						neicun[1] = mavlink_msg_mission_count_get_count(&msgin);
						//cpuzhizhen[1] = neicun[1];
						neicun[0] = 1;//响应标志位
						//cpuzhizhen[2]  ++;
						break;
					}
				case MAVLINK_MSG_ID_MISSION_CURRENT://任务数量
				{
					//cpuzhizhen[1] = mavlink_msg_mission_current_get_total(&msgin);//
					//cpuzhizhen[2]  ++;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_REQUEST://飞机请求任务
				{
					neicun[10] = 1;
					neicun[13] = mavlink_msg_mission_request_get_seq(&msgin);
					//cpuzhizhen[1] = mavlink_msg_mission_request_int_get_mission_type(&msgin);
					//cpuzhizhen[2]  ++;
					//neicun[0] = 1;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_REQUEST_INT://飞机请求任务
				{
					neicun[10] = 1;
					neicun[12] = mavlink_msg_mission_request_int_get_seq(&msgin);
					//cpuzhizhen[1] = mavlink_msg_mission_request_int_get_mission_type(&msgin);
					//cpuzhizhen[2]  ++;
					//neicun[0] = 1;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_ITEM_INT://飞机请求任务
				{
					neicun[101 + neicun[ 100 ]] = mavlink_msg_mission_item_int_get_z(&msgin);
					//cpuzhizhen[1] = mavlink_msg_mission_item_int_get_seq(&msgin);
					neicun[2] = 1;
					//cpuzhizhen[2]++;
					break;
				}
				case MAVLINK_MSG_ID_MISSION_ACK://飞机接收任务结束的指令ACK
				{
					neicun[12] = 1;
					//cpuzhizhen[1] = mavlink_msg_mission_item_int_get_seq(&msgin);
					//cpuzhizhen[2]++;
					break;
				}
				 default:
				 {

				 }
					break;
				}
			}
		}

	}