AP_Mission: Cleanup the header to reduce flash cost
Removes unneeded set's of memory that is already zero'd. It also changes
_flags to be all bool to match the actual usage, and removes the width
specifiers from them. This increases the RAM cost of AP_Mission by 4
bytes, but saves on flash. The RAM cost was eliminated by rearranging
members.
zr-v5.1
Michael du Breuil4 years agocommitted byAndrew Tridgell
AP_Int16_cmd_total;// total number of commands in the mission
AP_Int8_restart;// controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
AP_Int16_options;// bitmask options for missions, currently for mission clearing on reboot but can be expanded as required
// pointer to main program functions
mission_cmd_fn_t_cmd_start_fn;// pointer to function which will be called when a new command is started
mission_cmd_fn_t_cmd_verify_fn;// pointer to function which will be called repeatedly to ensure a command is progressing
mission_complete_fn_t_mission_complete_fn;// pointer to function which will be called when mission completes
// parameters
AP_Int16_cmd_total;// total number of commands in the mission
AP_Int16_options;// bitmask options for missions, currently for mission clearing on reboot but can be expanded as required
AP_Int8_restart;// controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
// internal variables
bool_force_resume;// when set true it forces mission to resume irrespective of MIS_RESTART param.
uint16_t_repeat_dist;// Distance to repeat on mission resume (m), can be set with MAV_CMD_DO_SET_RESUME_REPEAT_DIST
structMission_Command_nav_cmd;// current "navigation" command. It's position in the command list is held in _nav_cmd.index
structMission_Command_do_cmd;// current "do" command. It's position in the command list is held in _do_cmd.index
structMission_Command_resume_cmd;// virtual wp command that is used to resume mission if the mission needs to be rewound on resume.
uint16_t_prev_nav_cmd_id;// id of the previous "navigation" command. (WAYPOINT, LOITER_TO_ALT, ect etc)
uint16_t_prev_nav_cmd_index;// index of the previous "navigation" command. Rarely used which is why we don't store the whole command
uint16_t_prev_nav_cmd_wp_index;// index of the previous "navigation" command that contains a waypoint. Rarely used which is why we don't store the whole command
bool_force_resume;// when set true it forces mission to resume irrespective of MIS_RESTART param.
structLocation_exit_position;// the position in the mission that the mission was exited