PX4 Firmware
PX4 Autopilot Software http://px4.io
parameters.cpp File Reference
#include "param.h"
#include <parameters/px4_parameters.h>
#include "tinybson/tinybson.h"
#include <crc32.h>
#include <float.h>
#include <math.h>
#include <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/posix.h>
#include <px4_platform_common/sem.h>
#include <px4_platform_common/shutdown.h>
#include <systemlib/uthash/utarray.h>
#include "uORB/uORB.h"
#include "uORB/topics/parameter_update.h"
#include <uORB/topics/actuator_armed.h>
#include <uORB/Subscription.hpp>
#include <px4_platform_common/workqueue.h>
Include dependency graph for parameters.cpp:

Go to the source code of this file.

Classes

struct  autosave_work
 
struct  param_wbuf_s
 Storage for modified parameters. More...
 
struct  param_import_state
 

Macros

#define PARAM_OPEN   open
 
#define PARAM_CLOSE   close
 
#define param_info_count   px4_parameters.param_count
 

Functions

static int flash_param_save (bool only_unsaved)
 
static int flash_param_load ()
 
static int flash_param_import ()
 
static unsigned get_param_info_count ()
 
static void param_set_used_internal (param_t param)
 
static param_t param_find_internal (const char *name, bool notification)
 
static void param_lock_reader ()
 lock the parameter store for read access More...
 
static void param_lock_writer ()
 lock the parameter store for write access More...
 
static void param_unlock_reader ()
 unlock the parameter store More...
 
static void param_unlock_writer ()
 unlock the parameter store More...
 
static void param_assert_locked ()
 assert that the parameter store is locked More...
 
void param_init ()
 Initialize the param backend. More...
 
static bool handle_in_range (param_t param)
 Test whether a param_t is value. More...
 
static int param_compare_values (const void *a, const void *b)
 Compare two modifid parameter structures to determine ordering. More...
 
static param_wbuf_sparam_find_changed (param_t param)
 Locate the modified parameter structure for a parameter, if it exists. More...
 
static void _param_notify_changes ()
 
void param_notify_changes ()
 Notify the system about parameter changes. More...
 
param_t param_find (const char *name)
 Look up a parameter by name. More...
 
param_t param_find_no_notification (const char *name)
 Look up a parameter by name. More...
 
unsigned param_count ()
 Return the total number of parameters. More...
 
unsigned param_count_used ()
 Return the actually used number of parameters. More...
 
param_t param_for_index (unsigned index)
 Look up a parameter by index. More...
 
param_t param_for_used_index (unsigned index)
 Look up an used parameter by index. More...
 
int param_get_index (param_t param)
 Look up the index of a parameter. More...
 
int param_get_used_index (param_t param)
 Look up the index of an used parameter. More...
 
const char * param_name (param_t param)
 Obtain the name of a parameter. More...
 
bool param_is_volatile (param_t param)
 Obtain the volatile state of a parameter. More...
 
bool param_value_is_default (param_t param)
 Test whether a parameter's value has changed from the default. More...
 
bool param_value_unsaved (param_t param)
 Test whether a parameter's value has been changed but not saved. More...
 
param_type_t param_type (param_t param)
 Obtain the type of a parameter. More...
 
size_t param_size (param_t param)
 Determine the size of a parameter. More...
 
static const void * param_get_value_ptr (param_t param)
 Obtain a pointer to the storage allocated for a parameter. More...
 
int param_get (param_t param, void *val)
 Copy the value of a parameter. More...
 
static void autosave_worker (void *arg)
 worker callback method to save the parameters More...
 
static void param_autosave ()
 Automatically save the parameters after a timeout and limited rate. More...
 
void param_control_autosave (bool enable)
 Enable/disable the param autosaving. More...
 
static int param_set_internal (param_t param, const void *val, bool mark_saved, bool notify_changes)
 
int param_set (param_t param, const void *val)
 Set the value of a parameter. More...
 
int param_set_no_notification (param_t param, const void *val)
 Set the value of a parameter, but do not notify the system about the change. More...
 
bool param_used (param_t param)
 Wether a parameter is in use in the system. More...
 
void param_set_used (param_t param)
 Mark a parameter as used. More...
 
int param_reset (param_t param)
 Reset a parameter to its default value. More...
 
static void param_reset_all_internal (bool auto_save)
 
void param_reset_all ()
 Reset all parameters to their default values. More...
 
void param_reset_excludes (const char *excludes[], int num_excludes)
 Reset all parameters to their default values except for excluded parameters. More...
 
int param_set_default_file (const char *filename)
 Set the default parameter file name. More...
 
const char * param_get_default_file ()
 Get the default parameter file name. More...
 
int param_save_default ()
 Save parameters to the default file. More...
 
int param_load_default ()
 Load parameters from the default parameter file. More...
 
int param_export (int fd, bool only_unsaved)
 Export changed parameters to a file. More...
 
static int param_import_callback (bson_decoder_t decoder, void *priv, bson_node_t node)
 
static int param_import_internal (int fd, bool mark_saved)
 
int param_import (int fd)
 Import parameters from a file, discarding any unrecognized parameters. More...
 
int param_load (int fd)
 Load parameters from a file. More...
 
void param_foreach (void(*func)(void *arg, param_t param), void *arg, bool only_changed, bool only_used)
 Apply a function to each parameter. More...
 
uint32_t param_hash_check ()
 Generate the hash of all parameters and their values. More...
 
void param_print_status ()
 Print the status of the param system. More...
 

Variables

static const char * param_default_file = PX4_ROOTFSDIR"/eeprom/parameters"
 
static char * param_user_file = nullptr
 
static hrt_abstime last_autosave_timestamp = 0
 
static volatile bool autosave_scheduled = false
 
static bool autosave_disabled = false
 
static const param_info_sparam_info_base = (const param_info_s *) &px4_parameters
 Array of static parameter info. More...
 
uint8_t * param_changed_storage = nullptr
 
int size_param_changed_storage_bytes = 0
 
const int bits_per_allocation_unit = (sizeof(*param_changed_storage) * 8)
 
UT_arrayparam_values {nullptr}
 flexible array holding modified parameter values More...
 
const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr}
 array info for the modified parameters array More...
 
static orb_advert_t param_topic = nullptr
 parameter update topic handle More...
 
static unsigned int param_instance = 0
 
static px4_sem_t param_sem
 this protects against concurrent access to param_values More...
 
static int reader_lock_holders = 0
 
static px4_sem_t reader_lock_holders_lock
 this protects against concurrent access to reader_lock_holders More...
 
static perf_counter_t param_export_perf
 
static perf_counter_t param_find_perf
 
static perf_counter_t param_get_perf
 
static perf_counter_t param_set_perf
 
static px4_sem_t param_sem_save
 this protects against concurrent param saves (file or flash access). More...
 

Macro Definition Documentation

◆ PARAM_CLOSE

#define PARAM_CLOSE   close

Definition at line 90 of file parameters.cpp.

Referenced by param_load_default(), and param_save_default().

◆ param_info_count

#define param_info_count   px4_parameters.param_count

Definition at line 106 of file parameters.cpp.

Referenced by get_param_info_count().

◆ PARAM_OPEN

#define PARAM_OPEN   open

Definition at line 89 of file parameters.cpp.

Referenced by param_load_default(), and param_save_default().

Function Documentation

◆ _param_notify_changes()

static void _param_notify_changes ( )
static

Definition at line 301 of file parameters.cpp.

References hrt_absolute_time(), parameter_update_s::instance, orb_advertise(), ORB_ID, orb_publish(), param_instance, param_topic, and parameter_update_s::timestamp.

Referenced by param_notify_changes(), param_reset(), param_reset_all_internal(), param_reset_excludes(), and param_set_internal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ autosave_worker()

static void autosave_worker ( void *  arg)
static

worker callback method to save the parameters

Parameters
argunused

Definition at line 615 of file parameters.cpp.

References autosave_disabled, autosave_scheduled, hrt_absolute_time(), last_autosave_timestamp, ORB_ID, param_get_default_file(), param_lock_writer(), param_save_default(), and param_unlock_writer().

Referenced by param_autosave().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ flash_param_import()

static int flash_param_import ( )
inlinestatic

Definition at line 79 of file parameters.cpp.

Referenced by param_import().

Here is the caller graph for this function:

◆ flash_param_load()

static int flash_param_load ( )
inlinestatic

Definition at line 78 of file parameters.cpp.

Referenced by param_load(), and param_load_default().

Here is the caller graph for this function:

◆ flash_param_save()

static int flash_param_save ( bool  only_unsaved)
inlinestatic

Definition at line 77 of file parameters.cpp.

Referenced by param_export(), and param_save_default().

Here is the caller graph for this function:

◆ get_param_info_count()

static unsigned get_param_info_count ( )
static

Definition at line 124 of file parameters.cpp.

References bits_per_allocation_unit, param_changed_storage, param_info_count, and size_param_changed_storage_bytes.

Referenced by handle_in_range(), param_count(), param_count_used(), param_find_internal(), param_for_index(), and param_for_used_index().

Here is the caller graph for this function:

◆ handle_in_range()

static bool handle_in_range ( param_t  param)
static

Test whether a param_t is value.

Parameters
paramThe parameter handle to test.
Returns
True if the handle is valid.

Definition at line 249 of file parameters.cpp.

References get_param_info_count().

Referenced by param_foreach(), param_get_index(), param_get_value_ptr(), param_hash_check(), param_is_volatile(), param_name(), param_reset(), param_reset_excludes(), param_set_internal(), param_size(), and param_type().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_assert_locked()

static void param_assert_locked ( )
static

assert that the parameter store is locked

Definition at line 224 of file parameters.cpp.

Referenced by param_find_changed(), and param_get_value_ptr().

Here is the caller graph for this function:

◆ param_autosave()

static void param_autosave ( )
static

Automatically save the parameters after a timeout and limited rate.

This needs to be called with the writer lock held (it's not necessary that it's the writer lock, but it needs to be the same lock as autosave_worker() and param_control_autosave() use).

Definition at line 660 of file parameters.cpp.

References autosave_disabled, autosave_scheduled, autosave_worker(), hrt_abstime, hrt_elapsed_time(), and last_autosave_timestamp.

Referenced by param_reset(), param_reset_all_internal(), and param_set_internal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_compare_values()

static int param_compare_values ( const void *  a,
const void *  b 
)
static

Compare two modifid parameter structures to determine ordering.

This function is suitable for passing to qsort or bsearch.

Definition at line 261 of file parameters.cpp.

References param_wbuf_s::param.

Referenced by param_find_changed(), and param_set_internal().

Here is the caller graph for this function:

◆ param_control_autosave()

void param_control_autosave ( bool  enable)

Enable/disable the param autosaving.

Re-enabling with changed params will not cause an autosave.

Parameters
enabletrue: enable autosaving, false: disable autosaving

Definition at line 687 of file parameters.cpp.

References autosave_disabled, autosave_scheduled, param_lock_writer(), and param_unlock_writer().

Here is the call graph for this function:

◆ param_count()

unsigned param_count ( void  )

Return the total number of parameters.

Returns
The number of parameters.

Definition at line 382 of file parameters.cpp.

References get_param_info_count().

Referenced by param_print_status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_count_used()

unsigned param_count_used ( void  )

Return the actually used number of parameters.

Returns
The number of parameters.

Definition at line 388 of file parameters.cpp.

References bits_per_allocation_unit, get_param_info_count(), param_changed_storage, and size_param_changed_storage_bytes.

Referenced by param_print_status().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_export()

int param_export ( int  fd,
bool  only_unsaved 
)

Export changed parameters to a file.

Note: this method requires a large amount of stack size!

Parameters
fdFile descriptor to export to (-1 selects the FLASH storage).
only_unsavedOnly export changed parameters that have not yet been exported.
Returns
Zero on success, nonzero on failure.

Definition at line 1055 of file parameters.cpp.

References BSON_BIN_BINARY, bson_encoder_append_binary(), bson_encoder_append_double(), bson_encoder_append_int(), bson_encoder_fini(), bson_encoder_init_buf_file(), f(), param_value_u::f, flash_param_save(), param_value_u::i, name, param_wbuf_s::param, param_get_value_ptr(), param_lock_reader(), param_lock_writer(), param_name(), param_sem_save, param_size(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, PARAM_TYPE_STRUCT, PARAM_TYPE_STRUCT_MAX, param_unlock_reader(), param_unlock_writer(), param_values, perf_begin(), perf_end(), param_wbuf_s::unsaved, utarray_next, and param_wbuf_s::val.

Referenced by param_save_default().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_find()

param_t param_find ( const char *  name)

Look up a parameter by name.

Parameters
nameThe canonical name of the parameter being looked up.
Returns
A handle to the parameter, or PARAM_INVALID if the parameter does not exist. This call will also set the parameter as "used" in the system, which is used to e.g. show the parameter via the RC interface

Definition at line 370 of file parameters.cpp.

References param_find_internal().

Referenced by RCUpdate::initialize_parameter_handles(), sensors::initialize_parameter_handles(), and battery_status::initialize_parameter_handles().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_find_changed()

static param_wbuf_s* param_find_changed ( param_t  param)
static

Locate the modified parameter structure for a parameter, if it exists.

Parameters
paramThe parameter being searched.
Returns
The structure holding the modified value, or nullptr if the parameter has not been modified.

Definition at line 285 of file parameters.cpp.

References param_wbuf_s::param, param_assert_locked(), param_compare_values(), param_values, and utarray_find.

Referenced by param_foreach(), param_get_value_ptr(), param_reset(), param_set_internal(), param_value_is_default(), and param_value_unsaved().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_find_internal()

param_t param_find_internal ( const char *  name,
bool  notification 
)
static

Definition at line 329 of file parameters.cpp.

References get_param_info_count(), PARAM_INVALID, param_set_used_internal(), perf_begin(), and perf_end().

Referenced by param_find(), and param_find_no_notification().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_find_no_notification()

param_t param_find_no_notification ( const char *  name)

Look up a parameter by name.

Parameters
nameThe canonical name of the parameter being looked up.
Returns
A handle to the parameter, or PARAM_INVALID if the parameter does not exist.

Definition at line 376 of file parameters.cpp.

References param_find_internal().

Referenced by param_import_callback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_for_index()

param_t param_for_index ( unsigned  index)

Look up a parameter by index.

Parameters
indexAn index from 0 to n, where n is param_count()-1.
Returns
A handle to the parameter, or PARAM_INVALID if the index is out of range.

Definition at line 408 of file parameters.cpp.

References get_param_info_count(), and PARAM_INVALID.

Here is the call graph for this function:

◆ param_for_used_index()

param_t param_for_used_index ( unsigned  index)

Look up an used parameter by index.

Parameters
indexThe parameter to obtain the index for.
Returns
The index of the parameter in use, or -1 if the parameter does not exist.

Definition at line 420 of file parameters.cpp.

References bits_per_allocation_unit, get_param_info_count(), param_changed_storage, PARAM_INVALID, and size_param_changed_storage_bytes.

Here is the call graph for this function:

◆ param_foreach()

void param_foreach ( void(*)(void *arg, param_t param)  func,
void *  arg,
bool  only_changed,
bool  only_used 
)

Apply a function to each parameter.

Note that the parameter set is not locked during the traversal. It also does not hold an internal state, so the callback function can block or sleep between parameter callbacks.

Parameters
funcThe function to invoke for each parameter.
argArgument passed to the function.
only_changedIf true, the function is only called for parameters whose values have been changed from the default.
only_usedIf true, the function is only called for parameters which have been used in one of the running applications.

Definition at line 1353 of file parameters.cpp.

References handle_in_range(), param_find_changed(), and param_used().

Here is the call graph for this function:

◆ param_get()

int param_get ( param_t  param,
void *  val 
)

Copy the value of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
valWhere to return the value, assumed to point to suitable storage for the parameter type. For structures, a bitwise copy of the structure is performed to this address.
Returns
Zero if the parameter's value could be returned, nonzero otherwise.

Definition at line 589 of file parameters.cpp.

References param_get_value_ptr(), param_lock_reader(), param_size(), param_unlock_reader(), perf_begin(), and perf_end().

Referenced by battery_status::update_parameters(), sensors::update_parameters(), and RCUpdate::update_parameters().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_get_default_file()

const char* param_get_default_file ( void  )

Get the default parameter file name.

Returns
The path to the current default parameter file; either as a result of a call to param_set_default_file, or the built-in default.

Definition at line 968 of file parameters.cpp.

References param_default_file, and param_user_file.

Referenced by autosave_worker(), param_load_default(), param_print_status(), and param_save_default().

Here is the caller graph for this function:

◆ param_get_index()

int param_get_index ( param_t  param)

Look up the index of a parameter.

Parameters
paramThe parameter to obtain the index for.
Returns
The index, or -1 if the parameter does not exist.

Definition at line 449 of file parameters.cpp.

References handle_in_range(), and param_wbuf_s::param.

Referenced by param_set_used_internal(), and param_used().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_get_used_index()

int param_get_used_index ( param_t  param)

Look up the index of an used parameter.

Parameters
paramThe parameter to obtain the index for.
Returns
The index of the parameter in use, or -1 if the parameter does not exist.

Definition at line 459 of file parameters.cpp.

References bits_per_allocation_unit, param_changed_storage, param_used(), and size_param_changed_storage_bytes.

Here is the call graph for this function:

◆ param_get_value_ptr()

static const void* param_get_value_ptr ( param_t  param)
static

Obtain a pointer to the storage allocated for a parameter.

Parameters
paramThe parameter whose storage is sought.
Returns
A pointer to the parameter value, or nullptr if the parameter does not exist.

Definition at line 555 of file parameters.cpp.

References handle_in_range(), param_value_u::p, param_wbuf_s::param, param_assert_locked(), param_find_changed(), param_type(), PARAM_TYPE_STRUCT, PARAM_TYPE_STRUCT_MAX, param_wbuf_s::val, and param_info_s::val.

Referenced by param_export(), param_get(), param_hash_check(), and param_set_internal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_hash_check()

uint32_t param_hash_check ( void  )

Generate the hash of all parameters and their values.

Returns
CRC32 hash of all param_ids and values

Definition at line 1372 of file parameters.cpp.

References handle_in_range(), name, param_get_value_ptr(), param_is_volatile(), param_lock_reader(), param_name(), param_size(), param_unlock_reader(), and param_used().

Here is the call graph for this function:

◆ param_import()

int param_import ( int  fd)

Import parameters from a file, discarding any unrecognized parameters.

This function merges the imported parameters with the current parameter set.

Parameters
fdFile descriptor to import from (-1 selects the FLASH storage).
Returns
Zero on success, nonzero if an error occurred during import. Note that in the failure case, parameters may be inconsistent.

Definition at line 1332 of file parameters.cpp.

References flash_param_import(), and param_import_internal().

Here is the call graph for this function:

◆ param_import_callback()

static int param_import_callback ( bson_decoder_t  decoder,
void *  priv,
bson_node_t  node 
)
static

Definition at line 1183 of file parameters.cpp.

References BSON_BIN_BINARY, BSON_BINDATA, bson_decoder_copy_data(), bson_decoder_data_pending(), BSON_DOUBLE, BSON_EOO, BSON_INT32, bson_node_s::d, f(), bson_node_s::i, param_import_state::mark_saved, bson_node_s::name, param_find_no_notification(), PARAM_INVALID, param_name(), param_set_internal(), param_size(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, state, bson_node_s::subtype, and bson_node_s::type.

Referenced by param_import_internal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_import_internal()

static int param_import_internal ( int  fd,
bool  mark_saved 
)
static

Definition at line 1310 of file parameters.cpp.

References bson_decoder_init_file(), bson_decoder_next(), param_import_state::mark_saved, param_import_callback(), and state.

Referenced by param_import(), and param_load().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_init()

void param_init ( void  )

Initialize the param backend.

Call this on startup before calling any other methods.

Definition at line 230 of file parameters.cpp.

References param_sem, param_sem_save, PC_ELAPSED, perf_alloc, and reader_lock_holders_lock.

◆ param_is_volatile()

bool param_is_volatile ( param_t  param)

Obtain the volatile state of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
Returns
true if the parameter is volatile

Definition at line 492 of file parameters.cpp.

References handle_in_range(), param_wbuf_s::param, and param_info_s::volatile_param.

Referenced by param_hash_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_load()

int param_load ( int  fd)

Load parameters from a file.

This function resets all parameters to their default values, then loads new values from a file.

Parameters
fdFile descriptor to import from (-1 selects the FLASH storage).
Returns
Zero on success, nonzero if an error occurred during import. Note that in the failure case, parameters may be inconsistent.

Definition at line 1342 of file parameters.cpp.

References flash_param_load(), param_import_internal(), and param_reset_all_internal().

Referenced by param_load_default().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_load_default()

int param_load_default ( void  )

Load parameters from the default parameter file.

Returns
0 on success, 1 if all params have not yet been stored, -1 if device open failed, -2 if writing parameters failed

Definition at line 1022 of file parameters.cpp.

References flash_param_load(), PARAM_CLOSE, param_get_default_file(), param_load(), and PARAM_OPEN.

Here is the call graph for this function:

◆ param_lock_reader()

static void param_lock_reader ( )
static

lock the parameter store for read access

Definition at line 178 of file parameters.cpp.

References param_sem, reader_lock_holders, and reader_lock_holders_lock.

Referenced by param_export(), param_get(), param_hash_check(), param_value_is_default(), and param_value_unsaved().

Here is the caller graph for this function:

◆ param_lock_writer()

static void param_lock_writer ( )
static

lock the parameter store for write access

Definition at line 194 of file parameters.cpp.

References param_sem.

Referenced by autosave_worker(), param_control_autosave(), param_export(), param_reset(), param_reset_all_internal(), param_save_default(), and param_set_internal().

Here is the caller graph for this function:

◆ param_name()

const char* param_name ( param_t  param)

Obtain the name of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
Returns
The name assigned to the parameter, or NULL if the handle is invalid.

Definition at line 486 of file parameters.cpp.

References handle_in_range(), param_info_s::name, and param_wbuf_s::param.

Referenced by param_export(), param_hash_check(), param_import_callback(), and param_reset_excludes().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_notify_changes()

void param_notify_changes ( void  )

Notify the system about parameter changes.

Can be used for example after several calls to param_set_no_notification() to avoid unnecessary system notifications.

Definition at line 323 of file parameters.cpp.

References _param_notify_changes().

Here is the call graph for this function:

◆ param_print_status()

void param_print_status ( void  )

Print the status of the param system.

Definition at line 1395 of file parameters.cpp.

References autosave_disabled, hrt_elapsed_time(), last_autosave_timestamp, UT_array::n, param_count(), param_count_used(), param_get_default_file(), param_values, perf_print_counter(), and utarray_len.

Here is the call graph for this function:

◆ param_reset()

int param_reset ( param_t  param)

Reset a parameter to its default value.

This function frees any storage used by struct parameters, and returns the parameter to its default value.

Parameters
paramA handle returned by param_find or passed by param_foreach.
Returns
Zero on success, nonzero on failure

Definition at line 857 of file parameters.cpp.

References _param_notify_changes(), handle_in_range(), param_autosave(), param_find_changed(), param_lock_writer(), param_unlock_writer(), param_values, utarray_eltidx, and utarray_erase.

Referenced by param_reset_excludes().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_reset_all()

void param_reset_all ( void  )

Reset all parameters to their default values.

This function also releases the storage used by struct parameters.

Definition at line 910 of file parameters.cpp.

References param_reset_all_internal().

Here is the call graph for this function:

◆ param_reset_all_internal()

static void param_reset_all_internal ( bool  auto_save)
static

Definition at line 889 of file parameters.cpp.

References _param_notify_changes(), param_autosave(), param_lock_writer(), param_unlock_writer(), param_values, and utarray_free.

Referenced by param_load(), and param_reset_all().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_reset_excludes()

void param_reset_excludes ( const char *  excludes[],
int  num_excludes 
)

Reset all parameters to their default values except for excluded parameters.

This function also releases the storage used by struct parameters.

Parameters
excludesArray of param names to exclude from resetting. Use a wildcard at the end to exclude parameters with a certain prefix.
num_excludesThe number of excludes provided.

Definition at line 916 of file parameters.cpp.

References _param_notify_changes(), handle_in_range(), name, param_wbuf_s::param, param_name(), and param_reset().

Here is the call graph for this function:

◆ param_save_default()

int param_save_default ( void  )

Save parameters to the default file.

Note: this method requires a large amount of stack size!

This function saves all parameters with non-default values.

Returns
Zero on success.

Definition at line 974 of file parameters.cpp.

References fd, flash_param_save(), OK, PARAM_CLOSE, param_export(), param_get_default_file(), param_lock_writer(), PARAM_OPEN, param_unlock_writer(), perf_begin(), and perf_end().

Referenced by autosave_worker().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_set()

int param_set ( param_t  param,
const void *  val 
)

Set the value of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
valThe value to set; assumed to point to a variable of the parameter type. For structures, the pointer is assumed to point to a structure to be copied.
Returns
Zero if the parameter's value could be set from a scalar, nonzero otherwise.

Definition at line 814 of file parameters.cpp.

References param_set_internal().

Here is the call graph for this function:

◆ param_set_default_file()

int param_set_default_file ( const char *  filename)

Set the default parameter file name.

This has no effect if the FLASH-based storage is enabled.

Parameters
filenamePath to the default parameter file. The file is not required to exist.
Returns
Zero on success.

Definition at line 945 of file parameters.cpp.

References param_user_file.

◆ param_set_internal()

static int param_set_internal ( param_t  param,
const void *  val,
bool  mark_saved,
bool  notify_changes 
)
static

Definition at line 703 of file parameters.cpp.

References _param_notify_changes(), param_value_u::f, FLT_EPSILON, handle_in_range(), param_value_u::i, param_value_u::p, param_wbuf_s::param, param_autosave(), param_compare_values(), param_find_changed(), param_get_value_ptr(), param_get_value_ptr_external(), param_lock_writer(), param_set_external(), param_size(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, PARAM_TYPE_STRUCT, PARAM_TYPE_STRUCT_MAX, param_unlock_writer(), param_values, perf_begin(), perf_end(), param_wbuf_s::unsaved, utarray_new, utarray_push_back, utarray_sort, and param_wbuf_s::val.

Referenced by param_import_callback(), param_set(), and param_set_no_notification().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_set_no_notification()

int param_set_no_notification ( param_t  param,
const void *  val 
)

Set the value of a parameter, but do not notify the system about the change.

Parameters
paramA handle returned by param_find or passed by param_foreach.
valThe value to set; assumed to point to a variable of the parameter type. For structures, the pointer is assumed to point to a structure to be copied.
Returns
Zero if the parameter's value could be set from a scalar, nonzero otherwise.

Definition at line 820 of file parameters.cpp.

References param_set_internal().

Referenced by battery_status::update_parameters().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_set_used()

void param_set_used ( param_t  param)

Mark a parameter as used.

Only marked parameters will be sent to a GCS. A call to param_find() will mark a param as used as well.

Parameters
paramA handle returned by param_find or passed by param_foreach.

Definition at line 838 of file parameters.cpp.

References param_set_used_internal().

Here is the call graph for this function:

◆ param_set_used_internal()

void param_set_used_internal ( param_t  param)
static

Definition at line 843 of file parameters.cpp.

References bits_per_allocation_unit, param_changed_storage, and param_get_index().

Referenced by param_find_internal(), and param_set_used().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_size()

size_t param_size ( param_t  param)

Determine the size of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
Returns
The size of the parameter's value.

Definition at line 525 of file parameters.cpp.

References handle_in_range(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, PARAM_TYPE_STRUCT, and PARAM_TYPE_STRUCT_MAX.

Referenced by param_export(), param_get(), param_hash_check(), param_import_callback(), and param_set_internal().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_type()

param_type_t param_type ( param_t  param)

Obtain the type of a parameter.

Parameters
paramA handle returned by param_find or passed by param_foreach.
Returns
The type assigned to the parameter.

Definition at line 519 of file parameters.cpp.

References handle_in_range(), param_wbuf_s::param, PARAM_TYPE_UNKNOWN, and param_info_s::type.

Referenced by param_export(), param_get_value_ptr(), param_import_callback(), param_set_internal(), and param_size().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_unlock_reader()

static void param_unlock_reader ( )
static

unlock the parameter store

Definition at line 201 of file parameters.cpp.

References param_sem, reader_lock_holders, and reader_lock_holders_lock.

Referenced by param_export(), param_get(), param_hash_check(), param_value_is_default(), and param_value_unsaved().

Here is the caller graph for this function:

◆ param_unlock_writer()

static void param_unlock_writer ( )
static

unlock the parameter store

Definition at line 217 of file parameters.cpp.

References param_sem.

Referenced by autosave_worker(), param_control_autosave(), param_export(), param_reset(), param_reset_all_internal(), param_save_default(), and param_set_internal().

Here is the caller graph for this function:

◆ param_used()

bool param_used ( param_t  param)

Wether a parameter is in use in the system.

Returns
True if it has been written or read

Definition at line 826 of file parameters.cpp.

References bits_per_allocation_unit, param_changed_storage, and param_get_index().

Referenced by param_foreach(), param_get_used_index(), and param_hash_check().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ param_value_is_default()

bool param_value_is_default ( param_t  param)

Test whether a parameter's value has changed from the default.

Returns
If true, the parameter's value has not been changed from the default.

Definition at line 498 of file parameters.cpp.

References param_find_changed(), param_lock_reader(), and param_unlock_reader().

Here is the call graph for this function:

◆ param_value_unsaved()

bool param_value_unsaved ( param_t  param)

Test whether a parameter's value has been changed but not saved.

Returns
If true, the parameter's value has not been saved.

Definition at line 508 of file parameters.cpp.

References param_find_changed(), param_lock_reader(), param_unlock_reader(), and param_wbuf_s::unsaved.

Here is the call graph for this function:

Variable Documentation

◆ autosave_disabled

bool autosave_disabled = false
static

◆ autosave_scheduled

volatile bool autosave_scheduled = false
static

Definition at line 98 of file parameters.cpp.

Referenced by autosave_worker(), param_autosave(), and param_control_autosave().

◆ bits_per_allocation_unit

const int bits_per_allocation_unit = (sizeof(*param_changed_storage) * 8)

◆ last_autosave_timestamp

hrt_abstime last_autosave_timestamp = 0
static

Definition at line 96 of file parameters.cpp.

Referenced by autosave_worker(), param_autosave(), and param_print_status().

◆ param_changed_storage

uint8_t* param_changed_storage = nullptr

◆ param_default_file

const char* param_default_file = PX4_ROOTFSDIR"/eeprom/parameters"
static

Definition at line 80 of file parameters.cpp.

Referenced by param_get_default_file().

◆ param_export_perf

perf_counter_t param_export_perf
static

Definition at line 166 of file parameters.cpp.

◆ param_find_perf

perf_counter_t param_find_perf
static

Definition at line 167 of file parameters.cpp.

◆ param_get_perf

perf_counter_t param_get_perf
static

Definition at line 168 of file parameters.cpp.

◆ param_icd

const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr}

array info for the modified parameters array

Definition at line 147 of file parameters.cpp.

◆ param_info_base

const param_info_s* param_info_base = (const param_info_s *) &px4_parameters
static

Array of static parameter info.

Definition at line 105 of file parameters.cpp.

◆ param_instance

unsigned int param_instance = 0
static

Definition at line 152 of file parameters.cpp.

Referenced by _param_notify_changes().

◆ param_sem

px4_sem_t param_sem
static

this protects against concurrent access to param_values

Definition at line 162 of file parameters.cpp.

Referenced by param_init(), param_lock_reader(), param_lock_writer(), param_unlock_reader(), and param_unlock_writer().

◆ param_sem_save

px4_sem_t param_sem_save
static

this protects against concurrent param saves (file or flash access).

we use a separate lock to allow concurrent param reads and saves. a param_set could still be blocked by a param save, because it needs to take the reader lock

Definition at line 171 of file parameters.cpp.

Referenced by param_export(), and param_init().

◆ param_set_perf

perf_counter_t param_set_perf
static

Definition at line 169 of file parameters.cpp.

◆ param_topic

orb_advert_t param_topic = nullptr
static

parameter update topic handle

Definition at line 151 of file parameters.cpp.

Referenced by _param_notify_changes().

◆ param_user_file

char* param_user_file = nullptr
static

Definition at line 83 of file parameters.cpp.

Referenced by param_get_default_file(), and param_set_default_file().

◆ param_values

UT_array* param_values {nullptr}

flexible array holding modified parameter values

Definition at line 144 of file parameters.cpp.

Referenced by param_export(), param_find_changed(), param_print_status(), param_reset(), param_reset_all_internal(), and param_set_internal().

◆ reader_lock_holders

int reader_lock_holders = 0
static

Definition at line 163 of file parameters.cpp.

Referenced by param_lock_reader(), and param_unlock_reader().

◆ reader_lock_holders_lock

px4_sem_t reader_lock_holders_lock
static

this protects against concurrent access to reader_lock_holders

Definition at line 164 of file parameters.cpp.

Referenced by param_init(), param_lock_reader(), and param_unlock_reader().

◆ size_param_changed_storage_bytes

int size_param_changed_storage_bytes = 0