PX4 Firmware
PX4 Autopilot Software http://px4.io
parameters_shmem.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 <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 <perf/perf_counter.h>
#include <systemlib/uthash/utarray.h>
#include "uORB/uORB.h"
#include "uORB/topics/parameter_update.h"
#include <sys/stat.h>
#include <px4_platform_common/shmem.h>
#include <px4_platform_common/workqueue.h>
Include dependency graph for parameters_shmem.cpp:

Go to the source code of this file.

Classes

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 void init_params ()
 
static int param_set_internal (param_t param, const void *val, bool mark_saved, bool notify_changes)
 
static int param_load_default_no_notify ()
 
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 ()
 < we use a separate lock to allow concurrent param reads and saves. 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...
 
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...
 
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...
 
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 = "/usr/share/data/adsp/params"
 
static char * param_user_file = nullptr
 
static hrt_abstime last_autosave_timestamp = 0
 
static struct work_s autosave_work
 
static 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)
 
static unsigned char set_called_from_get = 0
 
static int param_import_done
 
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 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
 

Macro Definition Documentation

◆ PARAM_CLOSE

#define PARAM_CLOSE   close

Definition at line 91 of file parameters_shmem.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_shmem.cpp.

Referenced by get_param_info_count().

◆ PARAM_OPEN

#define PARAM_OPEN   open

Definition at line 89 of file parameters_shmem.cpp.

Referenced by param_load_default(), and param_save_default().

Function Documentation

◆ _param_notify_changes()

static void _param_notify_changes ( )
static

Definition at line 331 of file parameters_shmem.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 672 of file parameters_shmem.cpp.

References autosave_disabled, autosave_scheduled, hrt_absolute_time(), last_autosave_timestamp, 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:

◆ get_param_info_count()

static unsigned get_param_info_count ( )
static

Definition at line 134 of file parameters_shmem.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_for_index(), and param_for_used_index().

Here is the caller graph for this function:

◆ handle_in_range()

bool handle_in_range ( param_t  param)

Test whether a param_t is value.

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

Definition at line 279 of file parameters_shmem.cpp.

References get_param_info_count().

Referenced by param_find_internal(), param_foreach(), param_get(), 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:

◆ init_params()

void init_params ( )
static

Definition at line 1515 of file parameters_shmem.cpp.

References param_import_done, and param_load_default_no_notify().

Referenced by param_init().

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 248 of file parameters_shmem.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 702 of file parameters_shmem.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 291 of file parameters_shmem.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 729 of file parameters_shmem.cpp.

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

Referenced by ParameterTest::run_tests(), and TemperatureCalibration::task_main().

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

◆ param_count()

unsigned param_count ( void  )

Return the total number of parameters.

Returns
The number of parameters.

Definition at line 396 of file parameters_shmem.cpp.

References get_param_info_count().

Referenced by do_show(), do_show_all(), ParameterTest::exportImportAll(), param_print_status(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_untransmitted(), px4::logger::Logger::write_changed_parameters(), and px4::logger::Logger::write_parameters().

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 402 of file parameters_shmem.cpp.

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

Referenced by do_show(), do_show_all(), MavlinkParametersManager::handle_message(), param_print_status(), MavlinkParametersManager::send_one(), and MavlinkParametersManager::send_param().

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 1146 of file parameters_shmem.cpp.

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

Referenced by do_save(), ParameterTest::exportImportAll(), and 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 384 of file parameters_shmem.cpp.

References param_find_internal().

Referenced by DfMPU6050Wrapper::_update_accel_calibration(), DfLsm9ds1Wrapper::_update_accel_calibration(), DfMpu9250Wrapper::_update_accel_calibration(), DfMPU6050Wrapper::_update_gyro_calibration(), DfLsm9ds1Wrapper::_update_gyro_calibration(), DfMpu9250Wrapper::_update_gyro_calibration(), DfHmc5883Wrapper::_update_mag_calibration(), DfAK8963Wrapper::_update_mag_calibration(), DfLsm9ds1Wrapper::_update_mag_calibration(), DfMpu9250Wrapper::_update_mag_calibration(), arm_auth_init(), BATT_SMBUS::BATT_SMBUS(), control::BlockParamBase::BlockParamBase(), CameraCapture::CameraCapture(), CameraFeedback::CameraFeedback(), CameraTrigger::CameraTrigger(), circuit_breaker_enabled(), DfMpu9250Wrapper::DfMpu9250Wrapper(), do_accel(), do_accel_calibration(), do_airspeed_calibration(), do_compare(), do_gyro(), do_gyro_calibration(), do_level_calibration(), do_mag(), do_mag_calibration(), do_reset_nostart(), do_set(), do_touch(), do_trim_calibration(), PreFlightCheck::ekf2Check(), TemperatureCalibrationAccel::finish(), TemperatureCalibrationGyro::finish(), TemperatureCalibrationBaro::finish(), TemperatureCalibrationAccel::finish_sensor_instance(), TemperatureCalibrationGyro::finish_sensor_instance(), TemperatureCalibrationBaro::finish_sensor_instance(), FixedwingPositionControl::FixedwingPositionControl(), get_params(), CameraInterface::get_pins(), BATT_SMBUS::get_startup_info(), PreFlightCheck::imuConsistencyCheck(), INA226::INA226(), PX4FLOW::init(), SF0X::init(), TERARANGER::init(), SF1XX::init(), PMW3901::init(), PAW3902::init(), MK::init(), PX4IO::init(), UavcanNode::init(), sensors::TemperatureCompensation::initialize_parameter_handles(), GPS::initializeCommunicationDump(), vmount::InputMavlinkCmdMount::InputMavlinkCmdMount(), PX4IO::io_set_rc_config(), landing_target_estimator::LandingTargetEstimator::LandingTargetEstimator(), linux_pwm_out_main(), px4::logger::Logger::Logger(), mag_calibrate_all(), PreFlightCheck::magConsistencyCheck(), IridiumSBD::main_loop(), land_detector::MulticopterLandDetector::MulticopterLandDetector(), Navigator::Navigator(), uart_esc::parameters_init(), rc_receiver::parameters_init(), mpu9x50::parameters_init(), sensors::VotedSensorsUpdate::parametersUpdate(), ParameterTest::ParameterTest(), PrecLand::PrecLand(), PreFlightCheck::preflightCheck(), Simulator::publish_flow_topic(), RCUpdate::RCUpdate::rc_parameter_map_poll(), PreFlightCheck::rcCalibrationCheck(), read_accelerometer_avg(), px4::Replay::readAndApplyParameter(), RoboClaw::RoboClaw(), Commander::run(), GPS::run(), SF0X::Run(), TemperatureCalibrationBase::set_parameter(), px4::Replay::setUserParams(), ParameterTest::SimpleFind(), snapdragon_pwm_out_main(), Standard::Standard(), Tailsitter::Tailsitter(), TemperatureCalibration::task_main(), PX4IO::task_main(), task_main(), test_param(), Tiltrotor::Tiltrotor(), uavcan_main(), uavcannode_start(), RGBLED_NPC5623C::update_params(), RGBLED::update_params(), linux_pwm_out::update_params(), snapdragon_pwm::update_params(), PX4FMU::update_pwm_rev_mask(), PX4FMU::update_pwm_trims(), MulticopterAttitudeControl::vehicle_status_poll(), FixedwingAttitudeControl::vehicle_status_poll(), FixedwingPositionControl::vehicle_status_poll(), VtolAttitudeControl::VtolAttitudeControl(), px4::logger::Logger::write_version(), and BATT_SMBUS::~BATT_SMBUS().

Here is the call graph for this function:

◆ param_find_changed()

param_wbuf_s* param_find_changed ( param_t  param)

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 315 of file parameters_shmem.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 359 of file parameters_shmem.cpp.

References handle_in_range(), param_wbuf_s::param, 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 390 of file parameters_shmem.cpp.

References param_find_internal().

Referenced by PreFlightCheck::check_calibration(), do_find(), do_show_quiet(), MavlinkParametersManager::handle_message(), and 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 427 of file parameters_shmem.cpp.

References get_param_info_count(), and PARAM_INVALID.

Referenced by do_show_index(), ParameterTest::exportImportAll(), param_for_used_index(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_untransmitted(), px4::logger::Logger::write_changed_parameters(), and px4::logger::Logger::write_parameters().

Here is the call graph for this function:
Here is the caller 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 439 of file parameters_shmem.cpp.

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

Referenced by do_show_index(), MavlinkParametersManager::handle_message(), and RCUpdate::RCUpdate::rc_parameter_map_poll().

Here is the call graph for this function:
Here is the caller 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 1440 of file parameters_shmem.cpp.

References handle_in_range(), param_wbuf_s::param, param_find_changed(), and param_used().

Referenced by do_show(), and do_show_all().

Here is the call graph for this function:
Here is the caller 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 618 of file parameters_shmem.cpp.

References f(), handle_in_range(), param_value_u::i, param_get_value_ptr(), param_lock_reader(), param_name(), param_set_internal(), param_size(), param_type(), PARAM_TYPE_FLOAT, PARAM_TYPE_INT32, param_unlock_reader(), perf_begin(), perf_end(), and set_called_from_get.

Referenced by ParameterTest::_assert_parameter_float_value(), ParameterTest::_assert_parameter_int_value(), RoboClaw::_parameters_update(), DfMPU6050Wrapper::_update_accel_calibration(), DfLsm9ds1Wrapper::_update_accel_calibration(), DfMpu9250Wrapper::_update_accel_calibration(), DfMPU6050Wrapper::_update_gyro_calibration(), DfLsm9ds1Wrapper::_update_gyro_calibration(), DfMpu9250Wrapper::_update_gyro_calibration(), DfAK8963Wrapper::_update_mag_calibration(), DfHmc5883Wrapper::_update_mag_calibration(), DfLsm9ds1Wrapper::_update_mag_calibration(), DfMpu9250Wrapper::_update_mag_calibration(), land_detector::MulticopterLandDetector::_update_params(), landing_target_estimator::LandingTargetEstimator::_update_params(), arm_auth_update(), CameraCapture::CameraCapture(), CameraFeedback::CameraFeedback(), CameraTrigger::CameraTrigger(), PreFlightCheck::check_calibration(), circuit_breaker_enabled(), DfMpu9250Wrapper::DfMpu9250Wrapper(), do_accel(), do_accel_calibration(), do_airspeed_calibration(), do_compare(), do_gyro(), do_gyro_calibration(), do_level_calibration(), do_mag(), do_reset_nostart(), do_set(), do_show_index(), do_show_print(), do_show_quiet(), do_trim_calibration(), PreFlightCheck::ekf2Check(), ParameterTest::exportImport(), ParameterTest::exportImportAll(), px4::logger::Logger::get_log_file_name(), CameraInterface::get_pins(), BATT_SMBUS::get_startup_info(), PreFlightCheck::imuConsistencyCheck(), INA226::INA226(), PX4FLOW::init(), SF0X::init(), TERARANGER::init(), SF1XX::init(), PMW3901::init(), PAW3902::init(), FixedwingPositionControl::init(), PX4IO::init(), UavcanNode::init(), px4::logger::Logger::initialize_configured_topics(), sensors::TemperatureCompensation::initialize_parameter_handles(), GPS::initializeCommunicationDump(), vmount::InputMavlinkCmdMount::InputMavlinkCmdMount(), PX4IO::io_set_rc_config(), linux_pwm_out_main(), mag_calibrate_all(), PreFlightCheck::magConsistencyCheck(), IridiumSBD::main_loop(), sensors::TemperatureCompensation::parameters_update(), Tailsitter::parameters_update(), Tiltrotor::parameters_update(), Standard::parameters_update(), rc_receiver::parameters_update(), uart_esc::parameters_update(), mpu9x50::parameters_update(), VtolAttitudeControl::parameters_update(), sensors::VotedSensorsUpdate::parametersUpdate(), Navigator::params_update(), PreFlightCheck::preflightCheck(), Simulator::publish_flow_topic(), PreFlightCheck::rcCalibrationCheck(), read_accelerometer_avg(), Commander::run(), px4::logger::Logger::run(), GPS::run(), SF0X::Run(), MavlinkParametersManager::send_param(), ParameterTest::SimpleFind(), snapdragon_pwm_out_main(), TemperatureCalibration::task_main(), MK::task_main(), PX4IO::task_main(), task_main(), TEST_F(), test_param(), uavcan_main(), uavcannode_start(), control::BlockParam< float >::update(), RGBLED_NPC5623C::update_params(), RGBLED::update_params(), linux_pwm_out::update_params(), snapdragon_pwm::update_params(), update_params(), PX4FMU::update_pwm_rev_mask(), PX4FMU::update_pwm_trims(), PrecLand::updateParams(), MulticopterAttitudeControl::vehicle_status_poll(), FixedwingAttitudeControl::vehicle_status_poll(), px4::logger::Logger::write_changed_parameters(), px4::logger::Logger::write_parameters(), and px4::logger::Logger::write_version().

Here is the call 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 1029 of file parameters_shmem.cpp.

References param_default_file, and param_user_file.

Referenced by param_load_default(), param_load_default_no_notify(), param_main(), 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 472 of file parameters_shmem.cpp.

References handle_in_range(), and param_wbuf_s::param.

Referenced by do_show_index(), do_show_print(), 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 482 of file parameters_shmem.cpp.

References bits_per_allocation_unit, param_wbuf_s::param, param_changed_storage, param_used(), and size_param_changed_storage_bytes.

Referenced by do_show_index(), do_show_print(), and MavlinkParametersManager::send_param().

Here is the call graph for this function:
Here is the caller 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 584 of file parameters_shmem.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 1459 of file parameters_shmem.cpp.

References handle_in_range(), name, param_wbuf_s::param, param_get_value_ptr(), param_is_volatile(), param_lock_reader(), param_name(), param_size(), param_unlock_reader(), param_used(), and param_wbuf_s::val.

Referenced by MavlinkParametersManager::handle_message(), and MavlinkParametersManager::send_one().

Here is the call graph for this function:
Here is the caller 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 1421 of file parameters_shmem.cpp.

References flash_param_import(), and param_import_internal().

Referenced by do_import(), ParameterTest::exportImportAll(), and param_load_default_no_notify().

Here is the call graph for this function:
Here is the caller 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 1271 of file parameters_shmem.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_wbuf_s::param, 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 1398 of file parameters_shmem.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 254 of file parameters_shmem.cpp.

References init_params(), PC_ELAPSED, and perf_alloc.

Here is the call graph for this function:

◆ 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 521 of file parameters_shmem.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 1433 of file parameters_shmem.cpp.

References param_import_internal(), and param_reset_all_internal().

Referenced by do_load(), and 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 1078 of file parameters_shmem.cpp.

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

Referenced by commander_low_prio_loop(), ParameterTest::exportImport(), and ParameterTest::exportImportAll().

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

◆ param_load_default_no_notify()

static int param_load_default_no_notify ( )
static
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 1113 of file parameters_shmem.cpp.

References param_get_default_file(), and param_import().

Referenced by init_params().

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

◆ param_lock_reader()

static void param_lock_reader ( )
static

< 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 lock the parameter store for read access

Definition at line 189 of file parameters_shmem.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 208 of file parameters_shmem.cpp.

References param_sem.

Referenced by autosave_worker(), param_control_autosave(), param_reset(), param_reset_all_internal(), 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 515 of file parameters_shmem.cpp.

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

Referenced by do_compare(), do_set(), do_show_index(), do_show_print(), control::BlockParamBase::getName(), param_export(), param_export_internal(), param_get(), param_hash_check(), param_import_callback(), param_reset_excludes(), param_set_internal(), px4::Replay::readAndApplyParameter(), MavlinkParametersManager::send_param(), MavlinkParametersManager::send_untransmitted(), px4::Replay::setUserParams(), px4::logger::Logger::write_changed_parameters(), and px4::logger::Logger::write_parameters().

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 353 of file parameters_shmem.cpp.

References _param_notify_changes().

Referenced by do_accel_calibration(), do_gyro_calibration(), do_level_calibration(), do_mag_calibration(), and TemperatureCalibration::task_main().

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

◆ param_print_status()

void param_print_status ( void  )

Print the status of the param system.

Definition at line 1482 of file parameters_shmem.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.

Referenced by param_main().

Here is the call graph for this function:
Here is the caller 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 925 of file parameters_shmem.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(), and test_param().

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 978 of file parameters_shmem.cpp.

References param_reset_all_internal().

Referenced by commander_low_prio_loop(), do_reset(), do_reset_nostart(), ParameterTest::exportImportAll(), flash_param_load(), ParameterTest::ResetAll(), CollisionPreventionTest::SetUp(), ParameterTest::SetUp(), and ObstacleAvoidanceTest::SetUp().

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

◆ param_reset_all_internal()

static void param_reset_all_internal ( bool  auto_save)
static

Definition at line 957 of file parameters_shmem.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 984 of file parameters_shmem.cpp.

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

Referenced by do_reset(), do_reset_nostart(), ParameterTest::ResetAllExcludesBoundaryCheck(), ParameterTest::ResetAllExcludesOne(), ParameterTest::ResetAllExcludesTwo(), and ParameterTest::ResetAllExcludesWildcard().

Here is the call graph for this function:
Here is the caller 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 1035 of file parameters_shmem.cpp.

References fd, OK, PARAM_CLOSE, param_export(), param_get_default_file(), and PARAM_OPEN.

Referenced by autosave_worker(), commander_low_prio_loop(), do_airspeed_calibration(), do_save_default(), ParameterTest::exportImport(), ParameterTest::exportImportAll(), and TemperatureCalibration::task_main().

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 879 of file parameters_shmem.cpp.

References param_set_internal().

Referenced by ParameterTest::_set_all_int_parameters_to(), BATT_SMBUS::BATT_SMBUS(), control::BlockParam< float >::commit(), do_airspeed_calibration(), do_reset_nostart(), do_set(), do_trim_calibration(), MavlinkParametersManager::handle_message(), PX4IO::init(), mag_calibrate_all(), sensors::VotedSensorsUpdate::parametersUpdate(), px4::Replay::readAndApplyParameter(), Commander::run(), RCUpdate::RCUpdate::set_params_from_rc(), px4::Replay::setUserParams(), TEST_F(), test_param(), and BATT_SMBUS::~BATT_SMBUS().

Here is the call graph for this function:
Here is the caller 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 1013 of file parameters_shmem.cpp.

References param_user_file.

Referenced by param_main().

Here is the caller graph for this function:

◆ param_set_internal()

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

◆ 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 885 of file parameters_shmem.cpp.

References param_set_internal().

Referenced by CameraTrigger::CameraTrigger(), control::BlockParam< float >::commit_no_notification(), do_accel_calibration(), do_gyro_calibration(), do_level_calibration(), do_mag_calibration(), ParameterTest::exportImport(), ParameterTest::exportImportAll(), TemperatureCalibrationAccel::finish(), TemperatureCalibrationGyro::finish(), TemperatureCalibrationBaro::finish(), TemperatureCalibrationAccel::finish_sensor_instance(), TemperatureCalibrationGyro::finish_sensor_instance(), TemperatureCalibrationBaro::finish_sensor_instance(), PX4IO::init(), mag_calibrate_all(), sensors::VotedSensorsUpdate::parametersUpdate(), CameraTrigger::Run(), and TemperatureCalibrationBase::set_parameter().

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 906 of file parameters_shmem.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 911 of file parameters_shmem.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 554 of file parameters_shmem.cpp.

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

Referenced by do_show_print(), param_export(), param_export_internal(), 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 548 of file parameters_shmem.cpp.

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

Referenced by do_compare(), do_set(), do_show_index(), do_show_print(), do_show_quiet(), ParameterTest::exportImport(), ParameterTest::exportImportAll(), MavlinkParametersManager::handle_message(), param_export(), param_export_internal(), param_get(), param_get_value_ptr(), param_import_callback(), param_set_internal(), param_size(), MavlinkParametersManager::send_param(), px4::Replay::setUserParams(), test_param(), px4::logger::Logger::write_changed_parameters(), and px4::logger::Logger::write_parameters().

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 219 of file parameters_shmem.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 238 of file parameters_shmem.cpp.

References param_sem.

Referenced by autosave_worker(), param_control_autosave(), param_reset(), param_reset_all_internal(), 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 891 of file parameters_shmem.cpp.

References bits_per_allocation_unit, param_changed_storage, and param_get_index().

Referenced by do_show_index(), do_show_print(), param_foreach(), param_get_used_index(), param_hash_check(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_untransmitted(), px4::logger::Logger::write_changed_parameters(), and px4::logger::Logger::write_parameters().

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 527 of file parameters_shmem.cpp.

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

Referenced by do_compare(), do_set(), do_show_index(), and do_show_print().

Here is the call graph for this function:
Here is the caller 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 537 of file parameters_shmem.cpp.

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

Referenced by do_compare(), do_set(), do_show_index(), do_show_print(), MavlinkParametersManager::send_untransmitted(), and px4::logger::Logger::write_changed_parameters().

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

Variable Documentation

◆ autosave_disabled

bool autosave_disabled = false
static

◆ autosave_scheduled

bool autosave_scheduled = false
static

Definition at line 98 of file parameters_shmem.cpp.

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

◆ autosave_work

struct work_s autosave_work
static

Definition at line 97 of file parameters_shmem.cpp.

◆ 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_shmem.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 = "/usr/share/data/adsp/params"
static

Definition at line 81 of file parameters_shmem.cpp.

Referenced by param_get_default_file().

◆ param_export_perf

perf_counter_t param_export_perf
static

Definition at line 177 of file parameters_shmem.cpp.

◆ param_find_perf

perf_counter_t param_find_perf
static

Definition at line 178 of file parameters_shmem.cpp.

◆ param_get_perf

perf_counter_t param_get_perf
static

Definition at line 179 of file parameters_shmem.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 157 of file parameters_shmem.cpp.

◆ param_import_done

int param_import_done
static
Initial value:
=
0

Definition at line 128 of file parameters_shmem.cpp.

Referenced by init_params(), and param_set_internal().

◆ 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_shmem.cpp.

◆ param_instance

unsigned int param_instance = 0
static

Definition at line 162 of file parameters_shmem.cpp.

Referenced by _param_notify_changes().

◆ param_set_perf

perf_counter_t param_set_perf
static

Definition at line 180 of file parameters_shmem.cpp.

◆ param_topic

orb_advert_t param_topic = nullptr
static

parameter update topic handle

Definition at line 161 of file parameters_shmem.cpp.

Referenced by _param_notify_changes().

◆ param_user_file

char* param_user_file = nullptr
static

Definition at line 83 of file parameters_shmem.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 154 of file parameters_shmem.cpp.

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

◆ set_called_from_get

unsigned char set_called_from_get = 0
static

Definition at line 126 of file parameters_shmem.cpp.

Referenced by param_get(), and param_set_internal().

◆ size_param_changed_storage_bytes

int size_param_changed_storage_bytes = 0