PX4 Firmware
PX4 Autopilot Software http://px4.io
param.h File Reference

Global flash based parameter store. More...

#include <stdint.h>
#include <stdbool.h>
#include <sys/types.h>
Include dependency graph for param.h:

Go to the source code of this file.

Classes

union  param_value_u
 Parameter value union. More...
 
struct  param_info_s
 Static parameter definition structure. More...
 

Macros

#define PARAM_FILE_MAXSIZE   4096
 Maximum size of the parameter backing file. More...
 
#define PARAM_TYPE_INT32   0
 Parameter types. More...
 
#define PARAM_TYPE_FLOAT   1
 
#define PARAM_TYPE_STRUCT   100
 
#define PARAM_TYPE_STRUCT_MAX   (16384 + PARAM_TYPE_STRUCT)
 
#define PARAM_TYPE_UNKNOWN   (0xffff)
 
#define PARAM_INVALID   ((uint32_t)0xffffffff)
 Handle returned when a parameter cannot be found. More...
 
#define PARAM_HASH   ((uint32_t)INT32_MAX)
 Magic handle for hash check param. More...
 

Typedefs

typedef uint16_t param_type_t
 
typedef uint32_t param_t
 Parameter handle. More...
 

Functions

__EXPORT void param_init (void)
 Initialize the param backend. More...
 
__EXPORT param_t param_find (const char *name)
 Look up a parameter by name. More...
 
__EXPORT param_t param_find_no_notification (const char *name)
 Look up a parameter by name. More...
 
__EXPORT unsigned param_count (void)
 Return the total number of parameters. More...
 
__EXPORT unsigned param_count_used (void)
 Return the actually used number of parameters. More...
 
__EXPORT bool param_used (param_t param)
 Wether a parameter is in use in the system. More...
 
__EXPORT param_t param_for_index (unsigned index)
 Look up a parameter by index. More...
 
__EXPORT param_t param_for_used_index (unsigned index)
 Look up an used parameter by index. More...
 
__EXPORT int param_get_index (param_t param)
 Look up the index of a parameter. More...
 
__EXPORT int param_get_used_index (param_t param)
 Look up the index of an used parameter. More...
 
__EXPORT const char * param_name (param_t param)
 Obtain the name of a parameter. More...
 
__EXPORT bool param_is_volatile (param_t param)
 Obtain the volatile state of a parameter. More...
 
__EXPORT bool param_value_is_default (param_t param)
 Test whether a parameter's value has changed from the default. More...
 
__EXPORT bool param_value_unsaved (param_t param)
 Test whether a parameter's value has been changed but not saved. More...
 
__EXPORT param_type_t param_type (param_t param)
 Obtain the type of a parameter. More...
 
__EXPORT size_t param_size (param_t param)
 Determine the size of a parameter. More...
 
__EXPORT int param_get (param_t param, void *val)
 Copy the value of a parameter. More...
 
__EXPORT int param_set (param_t param, const void *val)
 Set the value of a parameter. More...
 
__EXPORT void param_set_used (param_t param)
 Mark a parameter as used. More...
 
__EXPORT 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...
 
__EXPORT void param_notify_changes (void)
 Notify the system about parameter changes. More...
 
__EXPORT int param_reset (param_t param)
 Reset a parameter to its default value. More...
 
__EXPORT void param_reset_all (void)
 Reset all parameters to their default values. More...
 
__EXPORT void param_reset_excludes (const char *excludes[], int num_excludes)
 Reset all parameters to their default values except for excluded parameters. More...
 
__EXPORT int param_export (int fd, bool only_unsaved)
 Export changed parameters to a file. More...
 
__EXPORT int param_import (int fd)
 Import parameters from a file, discarding any unrecognized parameters. More...
 
__EXPORT int param_load (int fd)
 Load parameters from a file. More...
 
__EXPORT 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...
 
__EXPORT int param_set_default_file (const char *filename)
 Set the default parameter file name. More...
 
__EXPORT const char * param_get_default_file (void)
 Get the default parameter file name. More...
 
__EXPORT int param_save_default (void)
 Save parameters to the default file. More...
 
__EXPORT int param_load_default (void)
 Load parameters from the default parameter file. More...
 
__EXPORT uint32_t param_hash_check (void)
 Generate the hash of all parameters and their values. More...
 
__EXPORT void param_print_status (void)
 Print the status of the param system. More...
 
__EXPORT void param_control_autosave (bool enable)
 Enable/disable the param autosaving. More...
 

Detailed Description

Global flash based parameter store.

Global parameter store.

This provides the mechanisms to interface to the PX4 parameter system but replace the IO with non file based flash i/o routines. So that the code my be implemented on a SMALL memory foot print device.

Note that a number of API members are marked const or pure; these assume that the set of parameters cannot change, or that a parameter cannot change type or size over its lifetime. If any of these assumptions are invalidated, the attributes should be re-evaluated.

Definition in file param.h.

Macro Definition Documentation

◆ PARAM_FILE_MAXSIZE

#define PARAM_FILE_MAXSIZE   4096

Maximum size of the parameter backing file.

Definition at line 53 of file param.h.

◆ PARAM_HASH

#define PARAM_HASH   ((uint32_t)INT32_MAX)

Magic handle for hash check param.

Definition at line 108 of file param.h.

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

◆ PARAM_INVALID

#define PARAM_INVALID   ((uint32_t)0xffffffff)

Handle returned when a parameter cannot be found.

Definition at line 103 of file param.h.

Referenced by control::BlockParamBase::BlockParamBase(), PreFlightCheck::check_calibration(), PrecLand::DEFINE_PARAMETERS(), DfMpu9250Wrapper::DfMpu9250Wrapper(), do_compare(), do_find(), do_set(), do_show_index(), do_show_quiet(), do_touch(), ParameterTest::exportImportAll(), FixedwingPositionControl::FixedwingPositionControl(), px4::logger::Logger::get_log_file_name(), get_params(), CameraInterface::get_pins(), MavlinkParametersManager::handle_message(), INA226::INA226(), PX4FLOW::init(), PMW3901::init(), PAW3902::init(), FixedwingPositionControl::init(), PX4IO::init(), px4::logger::Logger::initialize_configured_topics(), GPS::initializeCommunicationDump(), vmount::InputMavlinkCmdMount::InputMavlinkCmdMount(), param_find_internal(), param_for_index(), param_for_used_index(), param_import_callback(), Navigator::params_update(), PreFlightCheck::rcCalibrationCheck(), px4::Replay::readAndApplyParameter(), Commander::run(), px4::logger::Logger::run(), GPS::run(), MavlinkParametersManager::send_one(), MavlinkParametersManager::send_param(), MavlinkParametersManager::send_untransmitted(), ParameterTest::SimpleFind(), PX4IO::task_main(), test_param(), linux_pwm_out::update_params(), snapdragon_pwm::update_params(), PX4FMU::update_pwm_rev_mask(), PX4FMU::update_pwm_trims(), PrecLand::updateParams(), px4::logger::Logger::write_changed_parameters(), px4::logger::Logger::write_parameters(), and px4::logger::Logger::write_version().

◆ PARAM_TYPE_FLOAT

◆ PARAM_TYPE_INT32

◆ PARAM_TYPE_STRUCT

#define PARAM_TYPE_STRUCT   100

◆ PARAM_TYPE_STRUCT_MAX

#define PARAM_TYPE_STRUCT_MAX   (16384 + PARAM_TYPE_STRUCT)

◆ PARAM_TYPE_UNKNOWN

#define PARAM_TYPE_UNKNOWN   (0xffff)

Definition at line 64 of file param.h.

Referenced by param_type().

Typedef Documentation

◆ param_t

typedef uint32_t param_t

Parameter handle.

Parameters are represented by parameter handles, which can be obtained by looking up parameters. They are an offset into a global constant parameter array.

Definition at line 98 of file param.h.

◆ param_type_t

typedef uint16_t param_type_t

Definition at line 66 of file param.h.

Function Documentation

◆ param_control_autosave()

__EXPORT 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().

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()

__EXPORT 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 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()

__EXPORT 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 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()

__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(), bson_encoder_init_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 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()

__EXPORT 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 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(), RCUpdate::initialize_parameter_handles(), sensors::initialize_parameter_handles(), battery_status::initialize_parameter_handles(), 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_no_notification()

__EXPORT 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 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()

__EXPORT 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.

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()

__EXPORT 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_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()

__EXPORT 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_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()

__EXPORT 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 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(), battery_status::update_parameters(), sensors::update_parameters(), RCUpdate::update_parameters(), 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()

__EXPORT 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_load_default_no_notify(), param_main(), param_print_status(), and param_save_default().

Here is the caller graph for this function:

◆ param_get_index()

__EXPORT 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 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()

__EXPORT 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_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_hash_check()

__EXPORT 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_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()

__EXPORT 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().

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_init()

__EXPORT 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 init_params(), param_sem, param_sem_save, PC_ELAPSED, perf_alloc, and reader_lock_holders_lock.

Here is the call graph for this function:

◆ param_is_volatile()

__EXPORT 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()

__EXPORT 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 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()

__EXPORT int param_load_default ( void  )

Load parameters from the default parameter file.

Returns
Zero on success.
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.

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_name()

__EXPORT 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 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()

__EXPORT 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().

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()

__EXPORT 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.

Referenced by param_main().

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

◆ param_reset()

__EXPORT 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(), and test_param().

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

◆ param_reset_all()

__EXPORT 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().

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_excludes()

__EXPORT 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().

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()

__EXPORT 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(), 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()

__EXPORT 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().

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()

__EXPORT 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.

Referenced by param_main().

Here is the caller graph for this function:

◆ param_set_no_notification()

__EXPORT 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 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(), TemperatureCalibrationBase::set_parameter(), and battery_status::update_parameters().

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

◆ param_set_used()

__EXPORT 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_size()

__EXPORT 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 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()

__EXPORT 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 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_used()

__EXPORT 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 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()

__EXPORT 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().

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()

__EXPORT 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.

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: