mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Mission: save flash space when scripting not enabled
This commit is contained in:
parent
d832b41262
commit
41bc08e132
@ -1214,6 +1214,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||
cmd.content.scripting.p3 = packet.param4;
|
||||
break;
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_NAV_SCRIPT_TIME:
|
||||
cmd.content.nav_script_time.command = packet.param1;
|
||||
cmd.content.nav_script_time.timeout_s = packet.param2;
|
||||
@ -1222,6 +1223,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
||||
cmd.content.nav_script_time.arg3 = int16_t(packet.x);
|
||||
cmd.content.nav_script_time.arg4 = int16_t(packet.y);
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_NAV_ATTITUDE_TIME:
|
||||
cmd.content.nav_attitude_time.time_sec = constrain_float(packet.param1, 0, UINT16_MAX);
|
||||
@ -1708,6 +1710,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||
packet.param4 = cmd.content.scripting.p3;
|
||||
break;
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_NAV_SCRIPT_TIME:
|
||||
packet.param1 = cmd.content.nav_script_time.command;
|
||||
packet.param2 = cmd.content.nav_script_time.timeout_s;
|
||||
@ -1716,6 +1719,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
||||
packet.x = cmd.content.nav_script_time.arg3;
|
||||
packet.y = cmd.content.nav_script_time.arg4;
|
||||
break;
|
||||
#endif
|
||||
|
||||
case MAV_CMD_NAV_ATTITUDE_TIME:
|
||||
packet.param1 = cmd.content.nav_attitude_time.time_sec;
|
||||
@ -2470,8 +2474,10 @@ const char *AP_Mission::Mission_Command::type() const
|
||||
return "Jump";
|
||||
case MAV_CMD_DO_GO_AROUND:
|
||||
return "Go Around";
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
case MAV_CMD_NAV_SCRIPT_TIME:
|
||||
return "NavScriptTime";
|
||||
#endif
|
||||
case MAV_CMD_NAV_ATTITUDE_TIME:
|
||||
return "NavAttitudeTime";
|
||||
case MAV_CMD_DO_PAUSE_CONTINUE:
|
||||
@ -2642,7 +2648,9 @@ bool AP_Mission::calc_rewind_pos(Mission_Command& rewind_cmd)
|
||||
void AP_Mission::format_conversion(uint8_t tag_byte, const Mission_Command &cmd, PackedContent &packed_content) const
|
||||
{
|
||||
// currently only one conversion needed, more can be added
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
if (tag_byte == 0 && cmd.id == MAV_CMD_NAV_SCRIPT_TIME) {
|
||||
// PARAMETER_CONVERSION: conversion code added Oct 2022
|
||||
struct nav_script_time_Command_tag0 old_fmt;
|
||||
struct nav_script_time_Command new_fmt;
|
||||
memcpy((void*)&old_fmt, packed_content.bytes, sizeof(old_fmt));
|
||||
@ -2654,6 +2662,7 @@ void AP_Mission::format_conversion(uint8_t tag_byte, const Mission_Command &cmd,
|
||||
new_fmt.arg4 = 0;
|
||||
memcpy(packed_content.bytes, (void*)&new_fmt, sizeof(new_fmt));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
// singleton instance
|
||||
|
@ -221,6 +221,7 @@ public:
|
||||
float p3;
|
||||
};
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// Scripting NAV command old version of storage format
|
||||
struct PACKED nav_script_time_Command_tag0 {
|
||||
uint8_t command;
|
||||
@ -239,6 +240,7 @@ public:
|
||||
int16_t arg3;
|
||||
int16_t arg4;
|
||||
};
|
||||
#endif
|
||||
|
||||
// Scripting NAV command (with verify)
|
||||
struct PACKED nav_attitude_time_Command {
|
||||
@ -329,8 +331,10 @@ public:
|
||||
// do scripting
|
||||
scripting_Command scripting;
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
// nav scripting
|
||||
nav_script_time_Command nav_script_time;
|
||||
#endif
|
||||
|
||||
// nav attitude time
|
||||
nav_attitude_time_Command nav_attitude_time;
|
||||
|
Loading…
Reference in New Issue
Block a user