Intro
Welcome to Part 2 of the “Parameters explained” series. This blog post will have a more in-depth look at the PX4 parameter system.
In Part 1, we talked about Parameters’ basic concepts and structure; if you haven’t read that already, we strongly advise you to read that first.
Parameter library
Getting started with this guide, the most fundamental parameter data structure is defined in the parameters library. Let’s check out where the parameter handle is defined (src/lib/parameters/param.h):
/**
* 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.
*/
typedef uint16_t param_t;
In that file, you can find this line that defines the parameter handle param_t as uint16_t. This means the handle is just a 16-bit unsigned integer. It basically stores the offset inside the parameter array generated during compile time. Remember that this handle will be your primary way to refer to a specific parameter in the source code.
There are also functions available to utilize this structure in the parameter class (src/lib/parameters/parameters.cpp).
const char *param_name(param_t param)
{
return handle_in_range(param) ? px4::parameters[param].name : nullptr;
}
The function above takes the parameter handle as an input. It checks if the handle is in the valid range, then returns the name by accessing the handle’s value in the parameter array px4::parameters.
But what is this px4::parameters array, you may ask? Let’s find out!
Parameter Array & Handles generated at compile time
PX4 generates many files at compile time, including the parameters array and handles!
If you build a SITL (Software In The Loop) Simulation, you will find the parameters array in the following file: build/px4_sitl_default/src/lib/parameters/px4_parameters.hpp.
Note, if you build for different targets like different flight controllers, the ‘px4_sitl_default’ part will have that target’s name as the folder name. For example, px4_fmu-v6x.
static constexpr param_info_s parameters[] = {
{
"ASPD_BETA_GATE",
.val = { .i = 1},
},
{
"ASPD_BETA_NOISE",
.val = { .f = 0.3 },
},
{
"ASPD_DO_CHECKS",
.val = { .i = 7},
},
{
"ASPD_FALLBACK_GW",
.val = { .i = 0},
},
{
"ASPD_FS_INNOV",
.val = { .f = 5. },
},
{
"ASPD_FS_INTEG",
.val = { .f = 10. },
},
{
"ASPD_FS_T_START",
.val = { .i = -1},
},
{
"ASPD_FS_T_STOP",
.val = { .i = 2},
},
// Continues
}
When building a target, the px4::params handles and the px4::parameters array is generated. Which includes all necessary parameters needed for the target you are building. The array consists of the name and default values for each parameter.
#include <math.h> // NAN
#include <stdint.h>
#include <parameters/param.h>
// DO NOT EDIT
// This file is autogenerated from parameters.xml
namespace px4 {
/// Enum with all parameters
enum class params : uint16_t {
ASPD_BETA_GATE,
ASPD_BETA_NOISE,
ASPD_DO_CHECKS,
ASPD_FALLBACK_GW,
ASPD_FS_INNOV,
ASPD_FS_INTEG,
ASPD_FS_T_START,
ASPD_FS_T_STOP,
// Continues
}
As already mentioned, parameters are only offsets in an array. So they are defined as an enum, meaning values get assigned starting from 0, and increments by 1. You can access them via : “px4::params::<param_name>”. Since they belong in the px4 namespace, in the params class.
Param Class interface
Using the Parameter library directly is the C language way of using parameters. Which requires you to store the param handle value to get and set new values.
But for the C++ classes, there is a more intuitive way to interface with parameters using additional classes that encapsulate the parameter itself.
The C++ interface for the parameter objects is located in platforms/common/include/px4_platform_common/param.h.
If we inspect the directory path, we can see the “common” directory. This means the file is required by all common platforms, including NuttX.
Note: The categorization of platforms is needed for PX4 because it can be built to run on Microcontrollers using NuttX and on your laptop using Posix!
Here you can check all the interfaces the ParamInt class has, for example:
template<px4::params p>
class Param<int32_t, p>
{
public:
// static type-check
static_assert(px4::parameters_type[(int)p] == PARAM_TYPE_INT32, "parameter type must be int32_t");
Param()
{
param_set_used(handle());
update();
}
int32_t get() const { return _val; }
const int32_t &reference() const { return _val; }
/// Store the parameter value to the parameter storage (@see param_set())
bool commit() const { return param_set(handle(), &_val) == 0; }
/// Store the parameter value to the parameter storage, w/o notifying the system (@see param_set_no_notification())
bool commit_no_notification() const { return param_set_no_notification(handle(), &_val) == 0; }
/// Set and commit a new value. Returns true if the value changed.
bool commit_no_notification(int32_t val)
{
if (val != _val) {
set(val);
commit_no_notification();
return true;
}
return false;
}
void set(int32_t val) { _val = val; }
void reset()
{
param_reset_no_notification(handle());
update();
}
bool update() { return param_get(handle(), &_val) == 0; }
param_t handle() const { return param_handle(p); }
private:
int32_t _val;
};
The structure is quite simple, and you can use get() and set() functions to interact with the parameter data itself. There are functions like reset, commit, and update to help you handle the parameter interface more intuitively.
How to define the Parameters
The PX4 User Guide already does a great job explaining how to create/define Parameters, and rather than replicating the content, we think its best if we link add a link to the document.
How Parameter Metadata and Files are generated
You may have noticed the gap between defining parameters and the compile-time generation of parameter handles, parameter array, and the metadata for QGC and PX4 User Documentation.
I decided to leave most of this part out since it is pretty complex and too detailed, but here are some main points about this process:
The commands used for processing the compile-time generation of parameter data are in src/lib/parameters/CMakeLists.txt.
First, all the modules used for the build target get bunched together into module_list.
Second, px_process_params.py processes all the parameters defined in the modules inside the module_list to create a parameters.xml file in the build folder. You can check the inner workings by visiting the file here :
Note, it uses the utility library in the src/lib/parameters/px4params folder to categorize and parse the metadata. You can find tags like reboot_required and group and the parsing mechanism defined in src/lib/parameters/px4params/srcparser.py for example.
Finally, src/lib/parameters/px_generate_params.py reads the parameters.xml file and creates the px4_parameters.hpp file that contains handles and the array.
This part can be very unintuitive, so feel free to dig into the source code I have linked to learn more about them yourself!
How Parameters are updated
We now have all the parameters parsed and defined. When you change a parameter during flight, you would want that change to come into effect immediately. This is the last missing piece of our puzzle. Let’s talk about how the parameters get updated!
PX4 User Documentation has a general parameter updating scheme explained here :
https://docs.px4.io/master/en/advanced/parameters_and_configurations.html#c-api
Here’s the summary: There is a uORB topic (real-time communication system PX4 uses) named parameter_update, which gets published when the user changes any parameter.
When working with parameters, it’s essential to understand that the code outside your current scope can change its value. For example, users setting the new value via QGC. Changes get distributed through the different components of PX4 with the help of uORB.
To detect a change in a parameter, you need to subscribe to the parameter_update uORB topic. This is the only way to guarantee the value of the param is up to date.
Let’s take a look at Flight Mode Manager’s header file to get some insight :
class FlightModeManager : public ModuleBase<FlightModeManager>, public ModuleParams, public px4::WorkItem
{
// Things we don’t care
void updateParams() override;
// Things we don’t care
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
// Things we don’t care
}
It has a subscription to the ‘parameter_update’ topic. The uORB::SubscriptionInterval wrapper class simply ensures that the topic will be checked for updates at max 1 Hz. Then it simply calls the ‘updateParams()’ function that handles the parameter updates when the topic is received.
void FlightModeManager::updateParams()
{
ModuleParams::updateParams();
if (isAnyTaskActive()) {
_current_task.task->handleParameterUpdate();
}
// Things we don’t care
}
Inside updateParams() of FlightModeManager, it calls the parent ModuleParams class’ updateParams() function. Also, it calls the handleParameterUpdate() function of the active Flight Task, which also basically calls updateParams() of that FlightTask object, since it’s also inherited from ModuleParams.
If you want to learn about Flight Tasks in PX4, visit the PX4 User Documentation here!
So what is this mysterious updateParams() function from the ModuleParams class?
class ModuleParams : public ListNode<ModuleParams *>
{
public:
virtual void updateParams()
{
for (const auto &child : _children) {
child->updateParams();
}
updateParamsImpl();
}
/**
* @brief The implementation for this is generated with the macro DEFINE_PARAMETERS()
*/
virtual void updateParamsImpl() {}
private:
List<ModuleParams *> _children;
};
updateParams() is the most fundamental function used by all modules to update its parameters, which is why it’s defined here. You would notice that it first calls the same function recursively through child objects, then it calls the updateParamsImpl() function.
The recursive behavior is defined so that a call to updateParam() from the highest level class can trigger also in all the modules it inherits. However, this behavior is not used so frequently in PX4, so we won’t focus on that.
Instead, let’s check out updateParamsImpl() which does all the work of updating parameters. Since it’s a virtual function, it gets overridden by the classes (e.g., FlightModeManager) that inherits this class.
Now, the final big question is, where is this “updateParamsImpl()” function defined? And for that, we will need to learn about parameters macro!
DEFINE_PARAMETERS macro
In every class that uses parameters, you will notice the “DEFINE_PARAMETERS” macro like the following inside the Flight Mode Manager. It lists all the parameters used in the class in the following style:
DEFINE_PARAMETERS(
(ParamFloat<px4::params::LNDMC_ALT_MAX>) _param_lndmc_alt_max,
(ParamInt<px4::params::MPC_POS_MODE>) _param_mpc_pos_mode
);
What does this macro do? It’s actually inside the file that has Parameter class definitions : “platforms/common/include/px4_platform_common/param.h”.
#define _DEFINE_SINGLE_PARAMETER(x) \
do_not_explicitly_use_this_namespace::PAIR(x);
#define _CALL_UPDATE(x) \
STRIP(x).update();
// define the parameter update method, which will update all parameters.
// It is marked as 'final', so that wrong usages lead to a compile error (see below)
#define _DEFINE_PARAMETER_UPDATE_METHOD(...) \
protected: \
void updateParamsImpl() final { \
APPLY_ALL(_CALL_UPDATE, __VA_ARGS__) \
} \
private:
// Define a list of parameters. This macro also creates code to update parameters.
// If you get a compile error like:
// error: virtual function ‘virtual void <class>::updateParamsImpl()’
// It means you have a custom inheritance tree (at least one class with params that inherits from another
// class with params) and you need to use DEFINE_PARAMETERS_CUSTOM_PARENT() for **all** classes in
// that tree.
#define DEFINE_PARAMETERS(...) \
APPLY_ALL(_DEFINE_SINGLE_PARAMETER, __VA_ARGS__) \
_DEFINE_PARAMETER_UPDATE_METHOD(__VA_ARGS__)
It can be very confusing at a first glance, but let’s observe how it works.
So when you use DEFINE_PARAMETERS(…), all the content you put in the parenthesis is now “__VA_ARGS__” to the macro. So with the parameter example above, it would essentially be replaced as:
APPLY_ALL(_DEFINE_SINGLE_PARAMETER, (ParamFloat<px4::params::LNDMC_ALT_MAX>) _param_lndmc_alt_max,
(ParamInt<px4::params::MPC_POS_MODE>) _param_mpc_pos_mode) \
_DEFINE_PARAMETER_UPDATE_METHOD((ParamFloat<px4::params::LNDMC_ALT_MAX>) _param_lndmc_alt_max,
(ParamInt<px4::params::MPC_POS_MODE>) _param_mpc_pos_mode)
Now you must be wondering what the APPLY_ALL is. It’s basically applying those macro functions like _DEFINE_SINGLE_PRAMETER to all the parameters supplied individually. It is defined inside the param_macros.h file, which you can check out here if you are curious (warning, It is quite cryptic!).
So this block essentially turns into :
ParamFloat<px4::params::LNDMC_ALT_MAX> _param_lndmc_alt_max;
ParamInt<px4::params::MPC_POS_MODE>_param_mpc_pos_mode);
protected: \
void updateParamsImpl() final { \
_param_lndmc_alt_max.update(); _param_mpc_pos_mode.update();\
} \
private:
I know there’s a lot that I have skipped, but if you go through two macro files (pram.h & param_macros.h), you will get a better understanding. Now, going back to the original code that utilized this DEFINE_PARAMETERS macro in the first place, this will come into a full circle as :
class FlightModeManager : public ModuleBase<FlightModeManager>, public ModuleParams, public px4::WorkItem
{
// Things we don’t care about too much for this blog post
ParamFloat<px4::params::LNDMC_ALT_MAX> _param_lndmc_alt_max;
ParamInt<px4::params::MPC_POS_MODE>_param_mpc_pos_mode);
protected: \
void updateParamsImpl() final { \
_param_lndmc_alt_max.update();
_param_mpc_pos_mode.update();\
} \
private:
}
And that’s it. That’s all the DEFINE_PARAMETERS macro does.
It first defines all these parameter class instances, each with its own unique parameter handle. Then, it creates a protected function called “updateParamsImpl()”. Sounds familiar? This was the function that was being called and defined in the ModuleParams class.
The actual update in parameters in each class is done via this function, which is hidden under the updateParams() function. And this is the hidden magic of the parameter update system using Macros.
And inside that updateParamsImpl(), each parameter class object is called with the .update() function so that it fetches the latest parameter through the Parameter Library that we discussed at the beginning of this blog post.
Thanks For Reading
Let me know what you think!
And that wraps up our guide; we covered a lot of content today: how parameter library is defined, the C++ class wrapper for parameters, metadata creation during compilation, and finally, the macro magic. Amazing!
I hope by now you have a sense of how the architecture works, but if I didn’t do a good job or if you see any room for improvement, let me know on the feedback survey below!
I would be so curious to hear what you thought about this post! and hope to count with you on the next post!
Junwoo
PS: You can find me on Dronecode Discord Server (click to get an invite)