Navigator: add NUM_MISSION_ITMES_SUPPORTED to kconfig

Signed-off-by: Silvan <silvan@auterion.com>

boards: increase max mission items for boards with >=1kb RAM to 1000

Signed-off-by: Silvan <silvan@auterion.com>

boards: increase NUM_MISSION_ITMES_SUPPORTED for SITL to 10000

Signed-off-by: Silvan <silvan@auterion.com>
This commit is contained in:
Silvan
2025-01-27 13:23:42 +01:00
committed by Silvan Fuhrer
parent b91e1cd482
commit 18b6a61788
14 changed files with 22 additions and 8 deletions
+1
View File
@@ -66,6 +66,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
@@ -65,6 +65,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
@@ -66,6 +66,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
+1
View File
@@ -63,6 +63,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
@@ -63,6 +63,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
@@ -63,6 +63,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
+1
View File
@@ -64,6 +64,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
+1
View File
@@ -65,6 +65,7 @@ CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
+1
View File
@@ -76,6 +76,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
+1
View File
@@ -77,6 +77,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=1000
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
+1
View File
@@ -41,6 +41,7 @@ CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_NUM_MISSION_ITMES_SUPPORTED=10000
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_REPLAY=y
+2 -2
View File
@@ -72,8 +72,8 @@ enum {
DM_KEY_SAFE_POINTS_STATE_MAX = 1,
DM_KEY_FENCE_POINTS_MAX = 64,
DM_KEY_FENCE_POINTS_STATE_MAX = 1,
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = CONFIG_NUM_MISSION_ITMES_SUPPORTED,
DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = CONFIG_NUM_MISSION_ITMES_SUPPORTED,
DM_KEY_MISSION_STATE_MAX = 1,
DM_KEY_COMPAT_MAX = 1
};
+9
View File
@@ -27,3 +27,12 @@ menuconfig NAVIGATOR_ADSB
---help---
Add support for acting on ADSB transponder_report or ADSB_VEHICLE MAVLink messages.
Actions are warnings, Loiter, Land and RTL without climb.
menuconfig NUM_MISSION_ITMES_SUPPORTED
int "Maximum number of mission items"
default 500
depends on MODULES_NAVIGATOR
---help---
This limit always applies if mission items are stored on the SD card or in RAM. It should be set
adequately per boards such that if the items are stored in RAM they still fit the available memory.
The runtime parameter to configure the storage option is `SYS_DM_BACKEND`.
-6
View File
@@ -46,12 +46,6 @@
#include <stdint.h>
#include <stdbool.h>
#if defined(__PX4_POSIX)
# define NUM_MISSIONS_SUPPORTED (UINT16_MAX-1) // This is allocated as needed.
#else
# define NUM_MISSIONS_SUPPORTED 500
#endif
/* compatible to mavlink MAV_CMD */
enum NAV_CMD {
NAV_CMD_IDLE = 0,