AP_Mission: use Float16_t for NAV_SCRIPT_TIME

This commit is contained in:
Andrew Tridgell 2022-10-14 07:30:41 +11:00
parent 4121cc464d
commit cc39bd08be
2 changed files with 13 additions and 6 deletions

View File

@ -1207,8 +1207,10 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
case MAV_CMD_NAV_SCRIPT_TIME:
cmd.content.nav_script_time.command = packet.param1;
cmd.content.nav_script_time.timeout_s = packet.param2;
cmd.content.nav_script_time.arg1 = packet.param3;
cmd.content.nav_script_time.arg2 = packet.param4;
cmd.content.nav_script_time.arg1.set(packet.param3);
cmd.content.nav_script_time.arg2.set(packet.param4);
cmd.content.nav_script_time.arg3.set(packet.x);
cmd.content.nav_script_time.arg4.set(packet.y);
break;
case MAV_CMD_NAV_ATTITUDE_TIME:
@ -1699,8 +1701,10 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
case MAV_CMD_NAV_SCRIPT_TIME:
packet.param1 = cmd.content.nav_script_time.command;
packet.param2 = cmd.content.nav_script_time.timeout_s;
packet.param3 = cmd.content.nav_script_time.arg1;
packet.param4 = cmd.content.nav_script_time.arg2;
packet.param3 = cmd.content.nav_script_time.arg1.get();
packet.param4 = cmd.content.nav_script_time.arg2.get();
packet.x = cmd.content.nav_script_time.arg3.get();
packet.y = cmd.content.nav_script_time.arg4.get();
break;
case MAV_CMD_NAV_ATTITUDE_TIME:

View File

@ -20,6 +20,7 @@
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <StorageManager/StorageManager.h>
#include <AP_Common/float16.h>
// definitions
#define AP_MISSION_EEPROM_VERSION 0x65AE // version number stored in first four bytes of eeprom. increment this by one when eeprom format is changed
@ -222,8 +223,10 @@ public:
struct PACKED nav_script_time_Command {
uint8_t command;
uint8_t timeout_s;
float arg1;
float arg2;
Float16_t arg1;
Float16_t arg2;
Float16_t arg3;
Float16_t arg4;
};
// Scripting NAV command (with verify)