Mission, Parameters & Motors

This section covers mission management, parameter system, and motor control.

AP_Mission (Mission Management)

Header: libraries/AP_Mission/AP_Mission.h

Description: Mission storage and execution system for autonomous flight.

class AP_Mission

Object managing Mission.

Public Functions

void init()

init - initialises this library including checks the version in eeprom matches this library

public mission methods

inline mission_state state() const

status - returns the status of the mission (i.e. Mission_Started, Mission_Complete, Mission_Stopped

inline uint16_t num_commands() const

num_commands - returns total number of commands in the mission this number includes offset 0, the home location

inline uint16_t num_commands_max() const

num_commands_max - returns maximum number of commands that can be stored

void start()

start - resets current commands to point to the beginning of the mission To-Do: should we validate the mission first and return true/false?

void stop()

stop - stops mission execution. subsequent calls to update() will have no effect until the mission is started or resumed

void resume()

resume - continues the mission execution from where we last left off previous running commands will be re-initialised

void start_or_resume()

start_or_resume - if MIS_AUTORESTART=0 this will call resume(), otherwise it will call start()

bool starts_with_takeoff_cmd()

check mission starts with a takeoff command

void reset()

reset - reset mission to the first command

bool clear()

clear - clears out mission

void truncate(uint16_t index)

truncate - truncate any mission items beyond given index

void update()

update - ensures the command queues are loaded with the next command and calls main programs command_init and command_verify functions to progress the mission should be called at 10hz or higher

bool add_cmd(Mission_Command &cmd)

public command methods add_cmd - adds a command to the end of the command list and writes to storage returns true if successfully added, false on failure cmd.index is updated with it’s new position in the mission

bool replace_cmd(uint16_t index, const Mission_Command &cmd)

replace_cmd - replaces the command at position ‘index’ in the command list with the provided cmd replacing the current active command will have no effect until the command is restarted returns true if successfully replaced, false on failure

inline const Mission_Command &get_current_nav_cmd() const

get_current_nav_cmd - returns the current “navigation” command

inline uint16_t get_current_nav_index() const

get_current_nav_index - returns the current “navigation” command index Note that this will return 0 if there is no command. This is used in MAVLink reporting of the mission command

inline uint16_t get_current_nav_id() const

get_current_nav_id - return the id of the current nav command

inline uint16_t get_prev_nav_cmd_id() const

get_prev_nav_cmd_id - returns the previous “navigation” command id if there was no previous nav command it returns AP_MISSION_CMD_ID_NONE we do not return the entire command to save on RAM

inline uint16_t get_prev_nav_cmd_index() const

get_prev_nav_cmd_index - returns the previous “navigation” commands index (i.e. position in the mission command list) if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE we do not return the entire command to save on RAM

inline uint16_t get_prev_nav_cmd_with_wp_index() const

get_prev_nav_cmd_with_wp_index - returns the previous “navigation” commands index that contains a waypoint (i.e. position in the mission command list) if there was no previous nav command it returns AP_MISSION_CMD_INDEX_NONE we do not return the entire command to save on RAM

bool get_next_nav_cmd(uint16_t start_index, Mission_Command &cmd)

get_next_nav_cmd - gets next “navigation” command found at or after start_index returns true if found, false if not found (i.e. reached end of mission command list) accounts for do_jump commands

int32_t get_next_ground_course_cd(int32_t default_angle)

get the ground course of the next navigation leg in centidegrees from 0 36000. Return default_angle if next navigation leg cannot be determined

inline const Mission_Command &get_current_do_cmd() const

get_current_do_cmd - returns active “do” command

inline uint16_t get_current_do_cmd_id() const

get_current_do_cmd_id - returns id of the active “do” command

bool read_cmd_from_storage(uint16_t index, Mission_Command &cmd) const

load_cmd_from_storage - load command from storage true is return if successful

void write_home_to_storage()

write_home_to_storage - writes the special purpose cmd 0 (home) to storage home is taken directly from ahrs

Public Static Functions

static bool is_nav_cmd(const Mission_Command &cmd)

is_nav_cmd - returns true if the command’s id is a “navigation” command, false if “do” or “conditional” command

Private Functions

bool write_cmd_to_storage(uint16_t index, const Mission_Command &cmd)

private methods write_cmd_to_storage - write a command to storage cmd.index is used to calculate the storage location true is returned if successful

void complete()

complete - mission is marked complete and clean-up performed including calling the mission_complete_fn

bool advance_current_nav_cmd(uint16_t starting_index = 0)

advance_current_nav_cmd - moves current nav command forward

do command will also be loaded accounts for do-jump commands

void advance_current_do_cmd()

advance_current_do_cmd - moves current do command forward accounts for do-jump commands returns true if successfully advanced (can it ever be unsuccessful?)

bool get_next_cmd(uint16_t start_index, Mission_Command &cmd, bool increment_jump_num_times_if_found, bool send_gcs_msg = true)

get_next_cmd - gets next command found at or after start_index returns true if found, false if not found (i.e. mission complete) accounts for do_jump commands increment_jump_num_times_if_found should be set to true if advancing the active navigation command

bool get_next_do_cmd(uint16_t start_index, Mission_Command &cmd)

get_next_do_cmd - gets next “do” or “conditional” command after start_index returns true if found, false if not found stops and returns false if it hits another navigation command before it finds the first do or conditional command accounts for do_jump commands but never increments the jump’s num_times_run (get_next_nav_cmd is responsible for this)

void init_jump_tracking()

jump handling methods

int16_t get_jump_times_run(const Mission_Command &cmd)

get_jump_times_run - returns number of times the jump command has been run return is signed to be consistent with do-jump cmd’s repeat count which can be -1 (to signify to repeat forever)

void increment_jump_times_run(Mission_Command &cmd, bool send_gcs_msg = true)

increment_jump_times_run - increments the recorded number of times the jump command has been run

void check_eeprom_version()

check_eeprom_version - checks version of missions stored in eeprom matches this library command list will be cleared if they do not match

bool is_takeoff_next(uint16_t start_index)

check if the next nav command is a takeoff, skipping delays

Private Static Functions

sanity checks that the masked fields are not NaN’s or infinite

struct Altitude_Wait
struct AuxFunction
struct Cam_Trigg_Distance
struct Change_Speed_Command
struct Conditional_Delay_Command
struct Conditional_Distance_Command
union Content
struct Digicam_Configure
struct Digicam_Control
struct Do_Engine_Control
struct Do_VTOL_Transition
struct gimbal_manager_pitchyaw_Command
struct Gripper_Command
struct Guided_Limits_Command
struct image_start_capture_Command
struct Jump_Command
struct jump_tracking_struct
struct Mission_Command
struct Mission_Flags
struct Mount_Control
struct nav_attitude_time_Command
struct Navigation_Delay_Command
struct Repeat_Relay_Command
struct Repeat_Servo_Command
struct scripting_Command
struct set_camera_focus_Command
struct set_camera_source_Command
struct set_camera_zoom_Command
struct Set_Relay_Command
struct Set_Servo_Command
struct Set_Yaw_Speed
struct video_start_capture_Command
struct video_stop_capture_Command
struct Winch_Command
struct Yaw_Command

Key Methods:

  • load_from_storage() - Load mission from storage

  • start() - Start mission execution

  • update() - Update mission state

  • pause() - Pause mission

  • resume() - Resume mission

  • reset() - Reset mission

Mission Commands:

  • NAV_WAYPOINT - Fly to waypoint

  • NAV_LOITER_UNLIM - Loiter indefinitely

  • NAV_LOITER_TURNS - Loiter for N turns

  • NAV_LOITER_TIME - Loiter for N seconds

  • NAV_RETURN_TO_LAUNCH - Return to home

  • NAV_LAND - Land at location

  • NAV_TAKEOFF - Takeoff

Usage Example:

AP_Mission *mission = AP_Mission::get_singleton();

// Load mission from storage
mission->load_from_storage();

// Start mission
mission->start();

// In main loop
mission->update();

// Get current command
AP_Mission::Mission_Command cmd;
if (mission->get_current_nav_cmd(cmd)) {
    // Process current command
}

AP_Param (Parameter System)

Header: libraries/AP_Param/AP_Param.h

Description: Parameter storage and management system for runtime configuration.

class AP_Param

Base class for variables.

Provides naming and lookup services for variables.

Subclassed by AP_ParamTBase< float, AP_PARAM_FLOAT >, AP_ParamTBase< T, PT >, AP_ParamV< T, PT >

Public Functions

void copy_name_info(const struct AP_Param::Info *info, const struct GroupInfo *ginfo, const struct GroupNesting &group_nesting, uint8_t idx, char *buffer, size_t bufferSize, bool force_scalar = false) const

Copy the variable’s name, prefixed by any containing group name, to a buffer.

If the variable has no name, the buffer will contain an empty string.

Note that if the combination of names is larger than the buffer, the result in the buffer will be truncated.

Parameters:
  • token – token giving current variable

  • buffer – The destination buffer

  • bufferSize – Total size of the destination buffer.

void copy_name_token(const ParamToken &token, char *buffer, size_t bufferSize, bool force_scalar = false) const

Copy the variable’s name, prefixed by any containing group name, to a buffer.

Uses token to look up AP_Param::Info for the variable

void notify() const

Notify GCS of current parameter value

void save_sync(bool force_save, bool send_to_gcs)

Save the current value of the variable to storage, synchronous API

Parameters:

force_save – If true then force save even if default

Returns:

True if the variable was saved successfully.

void save(bool force_save = false)

Save the current value of the variable to storage, async interface

Parameters:

force_save – If true then force save even if default

bool load(void)

Load the variable from EEPROM.

Returns:

True if the variable was loaded successfully.

float cast_to_float(enum ap_var_type type) const

cast a variable to a float given its type

Public Static Functions

static AP_Param *find(const char *name, enum ap_var_type *ptype, uint16_t *flags = nullptr)

Find a variable by name.

If the variable has no name, it cannot be found by this interface.

Parameters:
  • name – The full name of the variable to be found.

  • flags – If non-null will be filled with parameter flags

Returns:

A pointer to the variable, or nullptr if it does not exist.

static bool set_default_by_name(const char *name, float value)

set a default value by name

Parameters:
  • name – The full name of the variable to be found.

  • value – The default value

Returns:

true if the variable is found

static void set_defaults_from_table(const struct defaults_table_struct *table, uint8_t count)

set parameter defaults from a defaults_table_struct

Parameters:
  • table – pointer to array of defaults_table_struct structures

  • count – number of elements in table array

static bool set_by_name(const char *name, float value)

set a value by name

Parameters:
  • name – The full name of the variable to be found.

  • value – The new value

Returns:

true if the variable is found

static bool get(const char *name, float &value)

gat a value by name, used by scripting

Parameters:
  • name – The full name of the variable to be found.

  • value – A reference to the variable

Returns:

true if the variable is found

static bool set_and_save_by_name(const char *name, float value)

set and save a value by name

Parameters:
  • name – The full name of the variable to be found.

  • value – The new value

Returns:

true if the variable is found

static AP_Param *find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token)

Find a variable by index.

Parameters:

idx – The index of the variable

Returns:

A pointer to the variable, or nullptr if it does not exist.

static bool find_key_by_pointer_group(const void *ptr, uint16_t vindex, const struct GroupInfo *group_info, ptrdiff_t offset, uint16_t &key)

Find a variable by pointer

Parameters:

p – Pointer to variable

Returns:

key for variable

static bool find_top_level_key_by_pointer(const void *ptr, uint16_t &key)

Find key of top level group variable by pointer

Parameters:

p – Pointer to variable

Returns:

key for variable

static void flush(void)

flush all pending parameter saves used on reboot

static bool load_all()

Load all variables from EEPROM

This function performs a best-efforts attempt to load all of the variables from EEPROM. If some fail to load, their values will remain as they are.

Returns:

False if any variable failed to load

static void reload_defaults_file(bool last_pass)

reoad the hal.util defaults file. Called after pointer parameters have been allocated

static void erase_all(void)

Erase all variables in EEPROM.

static AP_Param *first(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr)

Returns the first variable

Returns:

The first variable in _var_info, or nullptr if there are none.

static inline AP_Param *next(ParamToken *token, enum ap_var_type *ptype)

Returns the next variable in _var_info, recursing into groups as needed

static AP_Param *next(ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val = nullptr)

Returns the next variable in _var_info, recursing into groups as needed

static AP_Param *next_scalar(ParamToken *token, enum ap_var_type *ptype, float *default_val = nullptr)

Returns the next scalar variable in _var_info, recursing into groups as needed

Returns the next scalar in _var_info, recursing into groups as needed

static uint8_t type_size(enum ap_var_type type)

get the size of a type in bytes

Private Functions

void add_vector3f_suffix(char *buffer, size_t buffer_size, uint8_t idx) const

add a _X, _Y, _Z suffix to the name of a Vector3f element

Parameters:
  • buffer

  • buffer_size

  • idx – Suffix: 0 –> _X; 1 –> _Y; 2 –> _Z; (other –> undefined)

Private Static Functions

static const struct GroupInfo *get_group_info(const struct GroupInfo &ginfo)

get group_info pointer based on flags

static const struct GroupInfo *get_group_info(const struct Info &ginfo)

get group_info pointer based on flags

static AP_Param *next_group(const uint16_t vindex, const struct GroupInfo *group_info, bool *found_current, const uint32_t group_base, const uint8_t group_shift, const ptrdiff_t group_offset, ParamToken *token, enum ap_var_type *ptype, bool skip_disabled, float *default_val)

Returns the next variable in a group, recursing into groups as needed

Private Static Attributes

static const uint8_t k_EEPROM_magic1 = 0x41

“AP”

static const uint8_t k_EEPROM_revision = 6

current format revision

struct ConversionInfo
struct defaults_list
struct defaults_table_struct
struct EEPROM_header

EEPROM header

This structure is placed at the head of the EEPROM to indicate that the ROM is formatted for AP_Param.

struct G2ObjectConversion
struct GroupInfo
struct GroupNesting
struct Info
struct Param_header
struct param_override
struct param_save
struct ParamToken
struct TopLevelObjectConversion

Key Methods:

  • find() - Find parameter by name

  • set() - Set parameter value

  • save() - Save parameter to storage

  • load() - Load parameter from storage

  • get() - Get parameter value

  • get_default() - Get default value

Parameter Types:

  • AP_Float - Float parameter

  • AP_Int8/AP_Int16/AP_Int32 - Integer parameters

  • AP_UInt8/AP_UInt16/AP_UInt32 - Unsigned integer

  • AP_Vector3f - Vector3f parameter

  • AP_Enum - Enumerated parameter

  • AP_Matrix3f - Matrix3f parameter

Usage Example:

// Find parameter
AP_Float *p_param = AP_Param::find<float>("PSC_VEL_P");
if (p_param) {
    float value = p_param->get();
    p_param->set(1.5f);
    p_param->save();
}

// Generic find
AP_Param *param = AP_Param::find("PSC_VEL_P");
if (param) {
    param->set(1.5f);
}

Related Classes:

  • AP_ParamT - Parameter template

  • AP_Enum - Enum parameter


AP_Rally (Rally Points)

Header: libraries/AP_Rally/AP_Rally.h

Description: Rally point storage for safe return-to-launch.

class AP_Rally

Object managing Rally Points.

Usage Example:

AP_Rally *rally = AP_Rally::get_singleton();

// Get rally point count
uint16_t count = rally->get_rally_point_count();

// Get rally point
Location rally_point;
if (rally->get_rally_point(0, rally_point)) {
    // Use rally point
}

AP_Motors (Motor Control)

Header: libraries/AP_Motors/AP_Motors.h

Description: Motor mixing and control for multirotor aircraft.

class AP_Motors

Subclassed by AP_MotorsHeli, AP_MotorsMulticopter

struct AP_Motors_limit

Specialized Classes:

  • AP_MotorsMulticopter - Multicopter motor control

  • AP_MotorsMatrix - Matrix motor mixing

  • AP_MotorsHeli - Helicopter motor control

  • AP_Motors6DOF - 6-DOF motor control

Key Methods:

  • armed() - Arm/disarm motors

  • set_throttle() - Set motor throttle (0-1)

  • set_roll() - Set roll input

  • set_pitch() - Set pitch input

  • set_yaw() - Set yaw input

  • output() - Output to motors

Usage Example:

AP_Motors *motors = AP_Motors::get_singleton();

// Arm motors
motors->armed(true);

// Set throttle (0.0 to 1.0)
motors->set_throttle(0.5f);

// Set attitude inputs
motors->set_roll(roll_input);    // -1 to 1
motors->set_pitch(pitch_input);  // -1 to 1
motors->set_yaw(yaw_input);      // -1 to 1

// Output to motors
motors->output();

// Disarm
motors->armed(false);

See Also

  • Control Libraries - Attitude and position control

  • Safety Systems - Arming system

  • AP_MotorsMulticopter - Multicopter-specific motor control

  • AP_MotorsMatrix - Matrix mixing for multicopters