Compare commits

...

2 Commits

Author SHA1 Message Date
Daniel Agar 6fd19df64e parameter server continued 2022-12-10 22:07:08 -05:00
Daniel Agar 481addbcac WIP: parameter server 2022-12-10 15:33:25 -05:00
26 changed files with 2625 additions and 2401 deletions
+2 -2
View File
@@ -182,8 +182,8 @@ set(msg_files
TrajectoryWaypoint.msg
TransponderReport.msg
TuneControl.msg
UavcanParameterRequest.msg
UavcanParameterValue.msg
ParameterRequest.msg
ParameterValue.msg
UlogStream.msg
UlogStreamAck.msg
UwbDistance.msg
+30
View File
@@ -0,0 +1,30 @@
# parameter request type
uint64 timestamp # time since system start (microseconds)
uint8 MESSAGE_TYPE_INVALID = 0
uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 1
uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 2
uint8 MESSAGE_TYPE_PARAM_SET = 3
uint8 message_type # message type
uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL
uint8 node_id # node ID
char[17] name # parameter name
int16 param_index # -1 if the param_id field should be used as identifier
uint8 TYPE_INVALID = 0
uint8 TYPE_BOOL = 1
uint8 TYPE_UINT8 = 2
uint8 TYPE_INT32 = 3
uint8 TYPE_INT64 = 4
uint8 TYPE_FLOAT32 = 5
uint8 TYPE_FLOAT64 = 6
uint8 type # parameter type
int64 int64_value # current value if param_type is int-like
float64 float64_value # current value if param_type is float-like
uint8 ORB_QUEUE_LENGTH = 4
# TOPICS parameter_request uavcan_parameter_request
+17
View File
@@ -0,0 +1,17 @@
# parameter response type
uint64 timestamp # time since system start (microseconds)
uint8 node_id # requester node ID
char[17] param_name # parameter name
int16 param_index # parameter index, if known
uint16 param_count # number of parameters exposed by the node
uint8 type # parameter type
int64 int64_value # current value if param_type is int-like
float64 float64_value # current value if param_type is float-like
# TOPICS parameter_value uavcan_parameter_value
-23
View File
@@ -1,23 +0,0 @@
# UAVCAN-MAVLink parameter bridge request type
uint64 timestamp # time since system start (microseconds)
uint8 MESSAGE_TYPE_PARAM_REQUEST_READ = 20 # MAVLINK_MSG_ID_PARAM_REQUEST_READ
uint8 MESSAGE_TYPE_PARAM_REQUEST_LIST = 21 # MAVLINK_MSG_ID_PARAM_REQUEST_LIST
uint8 MESSAGE_TYPE_PARAM_SET = 23 # MAVLINK_MSG_ID_PARAM_SET
uint8 message_type # MAVLink message type: PARAM_REQUEST_READ, PARAM_REQUEST_LIST, PARAM_SET
uint8 NODE_ID_ALL = 0 # MAV_COMP_ID_ALL
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name
int16 param_index # -1 if the param_id field should be used as identifier
uint8 PARAM_TYPE_UINT8 = 1 # MAV_PARAM_TYPE_UINT8
uint8 PARAM_TYPE_INT64 = 8 # MAV_PARAM_TYPE_INT64
uint8 PARAM_TYPE_REAL32 = 9 # MAV_PARAM_TYPE_REAL32
uint8 param_type # MAVLink parameter type
int64 int_value # current value if param_type is int-like
float32 real_value # current value if param_type is float-like
uint8 ORB_QUEUE_LENGTH = 4
-9
View File
@@ -1,9 +0,0 @@
# UAVCAN-MAVLink parameter bridge response type
uint64 timestamp # time since system start (microseconds)
uint8 node_id # UAVCAN node ID mapped from MAVLink component ID
char[17] param_id # MAVLink/UAVCAN parameter name
int16 param_index # parameter index, if known
uint16 param_count # number of parameters exposed by the node
uint8 param_type # MAVLink parameter type
int64 int_value # current value if param_type is int-like
float32 real_value # current value if param_type is float-like
+2 -2
View File
@@ -127,8 +127,6 @@ int px4_platform_init()
hrt_ioctl_init();
#endif
param_init();
/* configure CPU load estimation */
#ifdef CONFIG_SCHED_INSTRUMENTATION
cpuload_initialize_once();
@@ -185,6 +183,8 @@ int px4_platform_init()
uorb_start();
param_init();
px4_log_initialize();
#if defined(CONFIG_SYSTEM_CDCACM) && defined(CONFIG_BUILD_FLAT)
+2 -2
View File
@@ -44,12 +44,12 @@ int px4_platform_init(void)
{
hrt_init();
param_init();
px4::WorkQueueManagerStart();
uorb_start();
param_init();
px4_log_initialize();
return PX4_OK;
+29 -23
View File
@@ -691,7 +691,8 @@ UavcanNode::Run()
// Check for parameter requests (get/set/list)
if (_param_request_sub.updated() && !_param_list_in_progress && !_param_in_progress && !_count_in_progress) {
uavcan_parameter_request_s request{};
parameter_request_s request{};
_param_request_sub.copy(&request);
if (_param_counts[request.node_id]) {
@@ -699,14 +700,14 @@ UavcanNode::Run()
* We know how many parameters are exposed by this node, so
* process the request.
*/
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
uavcan::protocol::param::GetSet::Request req;
if (request.param_index >= 0) {
req.index = request.param_index;
} else {
req.name = (char *)request.param_id;
req.name = (char *)request.name;
}
int call_res = _param_getset_client.call(request.node_id, req);
@@ -719,24 +720,29 @@ UavcanNode::Run()
_param_index = request.param_index;
}
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_SET) {
uavcan::protocol::param::GetSet::Request req;
if (request.param_index >= 0) {
req.index = request.param_index;
} else {
req.name = (char *)request.param_id;
req.name = (char *)request.name;
}
if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_REAL32) {
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.real_value;
switch (request.type) {
case parameter_request_s::TYPE_BOOL:
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int64_value;
break;
} else if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_UINT8) {
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int_value;
case parameter_request_s::TYPE_FLOAT32:
case parameter_request_s::TYPE_FLOAT64:
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.float64_value;
break;
} else {
req.value.to<uavcan::protocol::param::Value::Tag::integer_value>() = request.int_value;
default:
req.value.to<uavcan::protocol::param::Value::Tag::integer_value>() = request.int64_value;
break;
}
// Set the dirty bit for this node
@@ -752,7 +758,7 @@ UavcanNode::Run()
_param_index = request.param_index;
}
} else if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
// This triggers the _param_list_in_progress case below.
_param_index = 0;
_param_list_in_progress = true;
@@ -762,8 +768,8 @@ UavcanNode::Run()
PX4_DEBUG("starting component-specific param list");
}
} else if (request.node_id == uavcan_parameter_request_s::NODE_ID_ALL) {
if (request.message_type == uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
} else if (request.node_id == parameter_request_s::NODE_ID_ALL) {
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST) {
/*
* This triggers the _param_list_in_progress case below,
* but additionally iterates over all active nodes.
@@ -1081,24 +1087,24 @@ UavcanNode::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param::G
if (result.isSuccessful()) {
uavcan::protocol::param::GetSet::Response param = result.getResponse();
uavcan_parameter_value_s response{};
parameter_value_s response{};
response.node_id = result.getCallID().server_node_id.get();
strncpy(response.param_id, param.name.c_str(), sizeof(response.param_id) - 1);
response.param_id[16] = '\0';
strncpy(response.param_name, param.name.c_str(), sizeof(response.param_name) - 1);
response.param_name[16] = '\0';
response.param_index = _param_index;
response.param_count = _param_counts[response.node_id];
if (param.value.is(uavcan::protocol::param::Value::Tag::integer_value)) {
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_INT64;
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>();
response.type = parameter_request_s::TYPE_INT64;
response.int64_value = param.value.to<uavcan::protocol::param::Value::Tag::integer_value>();
} else if (param.value.is(uavcan::protocol::param::Value::Tag::real_value)) {
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_REAL32;
response.real_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>();
response.type = parameter_request_s::TYPE_FLOAT32;
response.float64_value = param.value.to<uavcan::protocol::param::Value::Tag::real_value>();
} else if (param.value.is(uavcan::protocol::param::Value::Tag::boolean_value)) {
response.param_type = uavcan_parameter_request_s::PARAM_TYPE_UINT8;
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
response.type = parameter_request_s::TYPE_BOOL;
response.int64_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
}
_param_response_pub.publish(response);
+3 -3
View File
@@ -75,8 +75,8 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/uavcan_parameter_request.h>
#include <uORB/topics/uavcan_parameter_value.h>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/vehicle_command_ack.h>
using namespace time_literals;
@@ -266,7 +266,7 @@ private:
uORB::Subscription _vcmd_sub{ORB_ID(vehicle_command)};
uORB::Subscription _param_request_sub{ORB_ID(uavcan_parameter_request)};
uORB::Publication<uavcan_parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
/*
+1 -1
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2014-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
+6 -15
View File
@@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2017 - 2020 PX4 Development Team. All rights reserved.
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -159,31 +159,22 @@ else()
list(APPEND SRCS param_translation.cpp)
endif()
if(${PX4_PLATFORM} STREQUAL "nuttx")
add_subdirectory(flashparams)
# build user-side interface for protected build
if(NOT CONFIG_BUILD_FLAT)
list(APPEND SRCS parameters_ioctl.cpp)
add_library(usr_parameters usr_parameters_if.cpp px4_parameters.hpp)
add_dependencies(usr_parameters prebuild_targets)
target_compile_definitions(usr_parameters PRIVATE -DMODULE_NAME="usr_parameters")
endif()
endif()
# TODO: find a better way to do this
if(NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters STATIC EXCLUDE_FROM_ALL
${SRCS}
px4_parameters.hpp
ParameterServer.cpp
ParameterServer.hpp
)
target_link_libraries(parameters PRIVATE perf tinybson px4_platform)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters" -D__KERNEL__)
target_compile_definitions(parameters PRIVATE -DMODULE_NAME="parameters")
target_compile_options(parameters
PRIVATE
#-DDEBUG_BUILD
#${MAX_CUSTOM_OPT_LEVEL}
-Wno-cast-align # TODO: fix and enable
-Wno-sign-compare # TODO: fix and enable
)
@@ -193,7 +184,7 @@ endif()
add_dependencies(parameters prebuild_targets)
if(${PX4_PLATFORM} STREQUAL "nuttx")
target_link_libraries(parameters PRIVATE flashparams)
#target_link_libraries(parameters PRIVATE flashparams)
endif()
px4_add_functional_gtest(SRC ParameterTest.cpp LINKLIBS parameters)
File diff suppressed because it is too large Load Diff
+525
View File
@@ -0,0 +1,525 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <px4_platform_common/atomic_bitset.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 <containers/Bitset.hpp>
#include <drivers/drv_hrt.h>
#include <lib/perf/perf_counter.h>
#include "tinybson/tinybson.h"
#include "uthash/utarray.h"
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionCallback.hpp>
#include <uORB/topics/actuator_armed.h>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/parameter_update.h>
#include "param.h"
#include <parameters/px4_parameters.hpp>
using namespace time_literals;
class ParameterServer : public px4::ScheduledWorkItem
{
public:
ParameterServer();
~ParameterServer() override;
/**
* Look up a parameter by name.
*
* @param name The canonical name of the parameter being looked up.
* @return A handle to the parameter, or PARAM_INVALID if the parameter does not exist.
*/
param_t findParameter(const char *name, bool notification = true);
/**
* Return the total number of parameters.
*
* @return The number of parameters.
*/
unsigned count() const { return param_info_count; }
/**
* Return the actually used number of parameters.
*
* @return The number of parameters.
*/
unsigned countUsed() const { return _params_active.count(); }
/**
* Wether a parameter is in use in the system.
*
* @return True if it has been written or read
*/
bool isParameterUsed(param_t param) const;
/**
* Look up a parameter by index.
*
* @param index An index from 0 to n, where n is param_count()-1.
* @return A handle to the parameter, or PARAM_INVALID if the index is out of range.
*/
param_t forIndex(unsigned index) const;
/**
* Look up an used parameter by index.
*
* @param index The parameter to obtain the index for.
* @return The index of the parameter in use, or -1 if the parameter does not exist.
*/
param_t forUsedIndex(unsigned index) const;
/**
* Look up the index of a parameter.
*
* @param param The parameter to obtain the index for.
* @return The index, or -1 if the parameter does not exist.
*/
int getParameterIndex(param_t param) const;
/**
* Look up the index of an used parameter.
*
* @param param The parameter to obtain the index for.
* @return The index of the parameter in use, or -1 if the parameter does not exist.
*/
int getParameterUsedIndex(param_t param) const;
/**
* Obtain the name of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The name assigned to the parameter, or NULL if the handle is invalid.
*/
const char *getParameterName(param_t param) const;
/**
* Obtain the volatile state of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return true if the parameter is volatile
*/
bool isParameterVolatile(param_t param) const;
/**
* Test whether a parameter's value has changed from the default.
*
* @return If true, the parameter's value has not been changed from the default.
*/
bool isParameterValueDefault(param_t param);
/**
* Test whether a parameter's value has been changed but not saved.
*
* @return If true, the parameter's value has not been saved.
*/
bool isParameterValueUnsaved(param_t param);
/**
* Obtain the type of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The type assigned to the parameter.
*/
param_type_t getParameterType(param_t param) const;
/**
* Determine the size of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return The size of the parameter's value.
*/
size_t getParameterSize(param_t param) const;
/**
* Copy the value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's value could be returned, nonzero otherwise.
*/
int getParameterValue(param_t param, void *val);
/**
* Copy the (airframe-specific) default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param default_val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's deafult value could be returned, nonzero otherwise.
*/
int getParameterDefaultValue(param_t param, void *default_val);
/**
* Copy the system-wide default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param default_val Where to return the value, assumed to point to suitable storage for the parameter type.
* @return Zero if the parameter's deafult value could be returned, nonzero otherwise.
*/
int getParameterSystemDefaultValue(param_t param, void *default_val);
/**
* Set the value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val The value to set; assumed to point to a variable of the parameter type.
* @return Zero if the parameter's value could be set from a scalar, nonzero otherwise.
*/
int setParameter(param_t param, const void *val, bool mark_saved = true, bool notify_changes = true);
/**
* Set the default value of a parameter.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @param val The default value to set; assumed to point to a variable of the parameter type.
* @return Zero if the parameter's default value could be set from a scalar, nonzero otherwise.
*/
int setParameterDefaultValue(param_t param, const void *val);
/**
* 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.
*
* @param param A handle returned by param_find or passed by param_foreach.
*/
void setParameterUsed(param_t param);
/**
* Notify the system about parameter changes. Can be used for example after several calls to
* param_set_no_notification() to avoid unnecessary system notifications.
*/
void notifyChanges();
/**
* Reset a parameter to its default value.
*
* @param param A handle returned by param_find or passed by param_foreach.
* @return Zero on success, nonzero on failure
*/
int resetParameter(param_t param, bool notify = true);
/**
* Reset all parameters to their default values.
*/
void resetAllParameters(bool auto_save = true);
/**
* Reset all parameters to their default values except for excluded parameters.
*
* @param excludes Array of param names to exclude from resetting. Use a wildcard
* at the end to exclude parameters with a certain prefix.
* @param num_excludes The number of excludes provided.
*/
void resetExcludes(const char *excludes[], int num_excludes);
/**
* Reset only specific parameters to their default values.
*
* @param resets Array of param names to reset. Use a wildcard at the end to reset parameters with a certain prefix.
* @param num_resets The number of passed reset conditions in the resets array.
*/
void resetSpecificParameter(const char *resets[], int num_resets);
/**
* Export changed parameters to a file.
* Note: this method requires a large amount of stack size!
*
* @param filename Path to the default parameter file.
* @param filter Filter parameters to be exported. The method should return true if
* the parameter should be exported. No filtering if nullptr is passed.
* @return Zero on success, nonzero on failure.
*/
typedef bool(*param_filter_func)(param_t handle);
int exportToFile(const char *filename, param_filter_func filter);
/**
* Import parameters from a file, discarding any unrecognized parameters.
*
* This function merges the imported parameters with the current parameter set.
*
* @param fd File descriptor to import from (-1 selects the FLASH storage).
* @return Zero on success, nonzero if an error occurred during import.
* Note that in the failure case, parameters may be inconsistent.
*/
int importFromFileDescriptor(int fd);
/**
* Load parameters from a file.
*
* This function resets all parameters to their default values, then loads new
* values from a file.
*
* @param fd File descriptor to import from (-1 selects the FLASH storage).
* @return Zero on success, nonzero if an error occurred during import.
* Note that in the failure case, parameters may be inconsistent.
*/
int loadFromFileDescriptor(int fd);
/**
* Read saved parameters from file and dump to console.
*
* This function reads the file and dumps all contents to console
* values from a file.
*
* @param fd File descriptor to read from.
* @return Zero on success, nonzero if an error occurred during import.
*/
int bsonDump(int fd);
/**
* 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.
*
* @param func The function to invoke for each parameter.
* @param arg Argument passed to the function.
* @param only_changed If true, the function is only called for parameters whose values have
* been changed from the default.
* @param only_used If true, the function is only called for parameters which have been
* used in one of the running applications.
*/
void forEachParameter(void (*func)(void *arg, param_t param), void *arg, bool only_changed, bool only_used);
/**
* Set the default parameter file name.
* This has no effect if the FLASH-based storage is enabled.
*
* @param filename Path to the default parameter file. The file is not required to
* exist.
* @return Zero on success.
*/
int setDefaultFile(const char *filename);
/**
* Get the default parameter file name.
*
* @return 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.
*/
const char *getDefaultFile() const { return _param_default_file; }
/**
* Set the backup parameter file name.
*
* @param filename Path to the backup parameter file. The file is not required to
* exist.
* @return Zero on success.
*/
int setBackupFile(const char *filename);
/**
* Get the backup parameter file name.
*
* @return The path to the backup parameter file
*/
const char *getBackupFile() const { return _param_backup_file; }
/**
* 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).
*/
void autoSave(bool now = false);
/**
* Load parameters from the default parameter file.
*
* @return Zero on success.
*/
int loadDefault();
/**
* Generate the hash of all parameters and their values
*
* @return CRC32 hash of all param_ids and values
*/
uint32_t hashCheck();
/**
* Print the status of the param system
*
*/
void printStatus();
/**
* Enable/disable the param autosaving.
* Re-enabling with changed params will not cause an autosave.
* @param enable true: enable autosaving, false: disable autosaving
*/
void controlAutosave(bool enable);
private:
static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s);
/**
* Test whether a param_t is value.
*
* @param param The parameter handle to test.
* @return True if the handle is valid.
*/
static constexpr bool handle_in_range(param_t param) { return (param < param_info_count); }
void lockReader(); // lock the parameter store for read access
void unlockReader(); // unlock the parameter store
void lockWriter(); // lock the parameter store for write access
void unlockWriter(); // unlock the parameter store
// Storage for modified parameters.
struct param_wbuf_s {
union param_value_u val {};
param_t param{PARAM_INVALID};
};
/**
* Compare two modified parameter structures to determine ordering.
*
* This function is suitable for passing to qsort or bsearch.
*/
static int compareValues(const void *a, const void *b);
/**
* Locate the modified parameter structure for a parameter, if it exists.
*
* @param param The parameter being searched.
* @return The structure holding the modified value, or
* nullptr if the parameter has not been modified.
*/
param_wbuf_s *findChanged(param_t param);
/**
* Obtain a pointer to the storage allocated for a parameter.
*
* @param param The parameter whose storage is sought.
* @return A pointer to the parameter value, or nullptr
* if the parameter does not exist.
*/
const void *getParameterValuePointer(param_t param);
// get parameter default value, caller is responsible for locking
int getParameterDefaultValueInternal(param_t param, void *default_val);
/**
* 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.
*
* @return Zero on success.
*/
int saveDefault();
// internal parameter export, caller is responsible for locking
int exportInternal(int fd, param_filter_func filter);
int bsonImportCallback(bson_decoder_t decoder, bson_node_t node);
static int importCallbackTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int importFromFileDescriptorInternal(int fd);
int verifyBsonExportCallback(bson_decoder_t decoder, bson_node_t node);
static int verifyBsonExportTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int verifyBsonExport(int fd);
static int bsonDumpCallbackTrampoline(bson_decoder_t decoder, void *priv, bson_node_t node);
int bsonDumpCallback(bson_decoder_t decoder, bson_node_t node);
char *_param_default_file{nullptr};
char *_param_backup_file{nullptr};
px4::AtomicBitset<param_info_count> _params_active; // params found
px4::AtomicBitset<param_info_count> _params_changed; // params non-default
px4::Bitset<param_info_count> _params_custom_default; // params with runtime default value
px4::AtomicBitset<param_info_count> _params_unsaved;
/** flexible array holding modified parameter values */
UT_array *_param_values{nullptr};
UT_array *_param_custom_default_values{nullptr};
const UT_icd param_icd = {sizeof(param_wbuf_s), nullptr, nullptr, nullptr};
unsigned int _param_instance{0};
// the following implements an RW-lock using 2 semaphores (used as mutexes). It gives
// priority to readers, meaning a writer could suffer from starvation, but in our use-case
// we only have short periods of reads and writes are rare.
px4_sem_t _param_sem; ///< this protects against concurrent access to _param_values
int _reader_lock_holders{0};
px4_sem_t _reader_lock_holders_lock; ///< this protects against concurrent access to reader_lock_holders
perf_counter_t _export_perf{perf_alloc(PC_ELAPSED, "param: export")};
perf_counter_t _find_count_perf{perf_alloc(PC_COUNT, "param: find")};
perf_counter_t _get_count_perf{perf_alloc(PC_COUNT, "param: get")};
perf_counter_t _set_perf{perf_alloc(PC_ELAPSED, "param: set")};
px4_sem_t _param_sem_save; ///< this protects against concurrent param saves (file or flash access).
///< we use a separate lock to allow concurrent param reads and saves.
///< a param_set could still be blocked by a param save, because it
///< needs to take the reader lock
void Run() override;
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(parameter_value)};
uORB::Publication<parameter_update_s> _parameter_update_pub{ORB_ID(parameter_update)};
uORB::SubscriptionCallbackWorkItem _param_request_sub{this, ORB_ID(parameter_request)};
uORB::SubscriptionData<actuator_armed_s> _armed_sub{ORB_ID(actuator_armed)};
// autosaving variables
hrt_abstime _last_autosave_timestamp{0};
px4::atomic_bool _autosave_scheduled{false};
bool _autosave_disabled{false};
px4::atomic_bool _notify_scheduled{false};
};
@@ -87,12 +87,12 @@ param_export_internal(param_filter_func filter)
bson_encoder_init_buf(&encoder, nullptr, 0);
/* no modified parameters -> we are done */
if (param_values == nullptr) {
if (_param_values == nullptr) {
result = 0;
goto out;
}
while ((s = (struct param_wbuf_s *)utarray_next(param_values, s)) != nullptr) {
while ((s = (struct param_wbuf_s *)utarray_next(_param_values, s)) != nullptr) {
int32_t i;
float f;
@@ -103,12 +103,12 @@ param_export_internal(param_filter_func filter)
/* append the appropriate BSON type object */
switch (param_type(s->param)) {
switch (getParameterType(s->param)) {
case PARAM_TYPE_INT32:
i = s->val.i;
if (bson_encoder_append_int32(&encoder, param_name(s->param), i)) {
debug("BSON append failed for '%s'", param_name(s->param));
if (bson_encoder_append_int32(&encoder, getParameterName(s->param), i)) {
debug("BSON append failed for '%s'", getParameterName(s->param));
goto out;
}
@@ -117,8 +117,8 @@ param_export_internal(param_filter_func filter)
case PARAM_TYPE_FLOAT:
f = s->val.f;
if (bson_encoder_append_double(&encoder, param_name(s->param), f)) {
debug("BSON append failed for '%s'", param_name(s->param));
if (bson_encoder_append_double(&encoder, getParameterName(s->param), f)) {
debug("BSON append failed for '%s'", getParameterName(s->param));
goto out;
}
@@ -214,7 +214,7 @@ param_import_callback(bson_decoder_t decoder, bson_node_t node)
switch (node->type) {
case BSON_INT32:
if (param_type(param) != PARAM_TYPE_INT32) {
if (getParameterType(param) != PARAM_TYPE_INT32) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
@@ -225,7 +225,7 @@ param_import_callback(bson_decoder_t decoder, bson_node_t node)
break;
case BSON_DOUBLE:
if (param_type(param) != PARAM_TYPE_FLOAT) {
if (getParameterType(param) != PARAM_TYPE_FLOAT) {
PX4_WARN("unexpected type for %s", node->name);
result = 1; // just skip this entry
goto out;
+1 -2
View File
@@ -303,8 +303,6 @@ __EXPORT void param_reset_all(void);
*/
__EXPORT void param_reset_excludes(const char *excludes[], int num_excludes);
typedef bool(*param_filter_func)(param_t handle);
/**
* Reset only specific parameters to their default values.
*
@@ -322,6 +320,7 @@ __EXPORT void param_reset_specific(const char *resets[], int num_resets);
* the parameter should be exported. No filtering if nullptr is passed.
* @return Zero on success, nonzero on failure.
*/
typedef bool(*param_filter_func)(param_t handle);
__EXPORT int param_export(const char *filename, param_filter_func filter);
/**
File diff suppressed because it is too large Load Diff
-139
View File
@@ -1,139 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <string.h>
/**
* @file parameters_common.cpp
*
* Global parameter store, functions common to kernel and user sides
*
*/
static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s);
/**
* Test whether a param_t is value.
*
* @param param The parameter handle to test.
* @return True if the handle is valid.
*/
static constexpr bool handle_in_range(param_t param) { return (param < param_info_count); }
unsigned param_count()
{
return param_info_count;
}
int param_get_index(param_t param)
{
if (handle_in_range(param)) {
return (unsigned)param;
}
return -1;
}
param_t param_for_index(unsigned index)
{
if (index < param_info_count) {
return (param_t)index;
}
return PARAM_INVALID;
}
const char *param_name(param_t param)
{
return handle_in_range(param) ? px4::parameters[param].name : nullptr;
}
param_type_t param_type(param_t param)
{
return handle_in_range(param) ? px4::parameters_type[param] : PARAM_TYPE_UNKNOWN;
}
bool param_is_volatile(param_t param)
{
if (handle_in_range(param)) {
for (const auto &p : px4::parameters_volatile) {
if (static_cast<px4::params>(param) == p) {
return true;
}
}
}
return false;
}
size_t param_size(param_t param)
{
if (handle_in_range(param)) {
switch (param_type(param)) {
case PARAM_TYPE_INT32:
case PARAM_TYPE_FLOAT:
return 4;
default:
return 0;
}
}
return 0;
}
int
param_get_system_default_value(param_t param, void *default_val)
{
if (!handle_in_range(param)) {
return PX4_ERROR;
}
int ret = PX4_OK;
switch (param_type(param)) {
case PARAM_TYPE_INT32:
memcpy(default_val, &px4::parameters[param].val.i, param_size(param));
break;
case PARAM_TYPE_FLOAT:
memcpy(default_val, &px4::parameters[param].val.f, param_size(param));
break;
default:
ret = PX4_ERROR;
break;
}
return ret;
}
-199
View File
@@ -1,199 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file parameters_ioctl.cpp
*
* Protected build kernel space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include <errno.h>
#include "param.h"
#include "parameters_ioctl.h"
#include <px4_platform_common/defines.h>
int param_ioctl(unsigned int cmd, unsigned long arg)
{
int ret = OK;
switch (cmd) {
case PARAMIOCNOTIFY: {
param_notify_changes();
}
break;
case PARAMIOCFIND: {
paramiocfind_t *data = (paramiocfind_t *)arg;
if (data->notification) {
data->ret = param_find(data->name);
} else {
data->ret = param_find_no_notification(data->name);
}
}
break;
case PARAMIOCCOUNTUSED: {
paramioccountused_t *data = (paramioccountused_t *)arg;
data->ret = param_count_used();
}
break;
case PARAMIOCFORUSEDINDEX: {
paramiocforusedindex_t *data = (paramiocforusedindex_t *)arg;
data->ret = param_for_used_index(data->index);
}
break;
case PARAMIOCGETUSEDINDEX: {
paramiocgetusedindex_t *data = (paramiocgetusedindex_t *)arg;
data->ret = param_get_used_index(data->param);
}
break;
case PARAMIOCUNSAVED: {
paramiocunsaved_t *data = (paramiocunsaved_t *)arg;
data->ret = param_value_unsaved(data->param);
}
break;
case PARAMIOCGET: {
paramiocget_t *data = (paramiocget_t *)arg;
if (data->deflt) {
data->ret = param_get_default_value(data->param, data->val);
} else {
data->ret = param_get(data->param, data->val);
}
}
break;
case PARAMIOCAUTOSAVE: {
paramiocautosave_t *data = (paramiocautosave_t *)arg;
param_control_autosave(data->enable);
}
break;
case PARAMIOCSET: {
paramiocset_t *data = (paramiocset_t *)arg;
if (data->notification) {
data->ret = param_set(data->param, data->val);
} else {
data->ret = param_set_no_notification(data->param, data->val);
}
}
break;
case PARAMIOCUSED: {
paramiocused_t *data = (paramiocused_t *)arg;
data->ret = param_used(data->param);
}
break;
case PARAMIOCSETUSED: {
paramiocsetused_t *data = (paramiocsetused_t *)arg;
param_set_used(data->param);
}
break;
case PARAMIOCSETDEFAULT: {
paramiocsetdefault_t *data = (paramiocsetdefault_t *)arg;
data->ret = param_set_default_value(data->param, data->val);
}
break;
case PARAMIOCRESET: {
paramiocreset_t *data = (paramiocreset_t *)arg;
if (data->notification) {
data->ret = param_reset(data->param);
} else {
data->ret = param_reset_no_notification(data->param);
}
}
break;
case PARAMIOCRESETGROUP: {
paramiocresetgroup_t *data = (paramiocresetgroup_t *)arg;
if (data->type == PARAM_RESET_EXCLUDES) {
param_reset_excludes(data->group, data->num_in_group);
} else if (data->type == PARAM_RESET_SPECIFIC) {
param_reset_specific(data->group, data->num_in_group);
} else {
param_reset_all();
}
}
break;
case PARAMIOCSAVEDEFAULT: {
paramiocsavedefault_t *data = (paramiocsavedefault_t *)arg;
data->ret = param_save_default();
}
break;
case PARAMIOCLOADDEFAULT: {
paramiocloaddefault_t *data = (paramiocloaddefault_t *)arg;
data->ret = param_load_default();
}
break;
case PARAMIOCEXPORT: {
paramiocexport_t *data = (paramiocexport_t *)arg;
data->ret = param_export(data->filename, nullptr);
}
break;
case PARAMIOCHASH: {
paramiochash_t *data = (paramiochash_t *)arg;
data->ret = param_hash_check();
}
break;
default:
ret = -ENOTTY;
break;
}
return ret;
}
-163
View File
@@ -1,163 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file parameters_ioctl.h
*
* User space - kernel space interface to global parameter store.
*/
#pragma once
#define PARAM_IMPLEMENTATION
#include "param.h"
#include <px4_platform/board_ctrl.h>
#include <px4_platform_common/defines.h>
#define _PARAMIOC(_n) (_PX4_IOC(_PARAMIOCBASE, _n))
#define PARAMIOCNOTIFY _PARAMIOC(1)
#define PARAMIOCFIND _PARAMIOC(2)
typedef struct paramiocfind {
const char *name;
const bool notification;
param_t ret;
} paramiocfind_t;
#define PARAMIOCCOUNTUSED _PARAMIOC(3)
typedef struct paramioccountused {
unsigned ret;
} paramioccountused_t;
#define PARAMIOCFORUSEDINDEX _PARAMIOC(4)
typedef struct paramiocforusedindex {
const unsigned index;
param_t ret;
} paramiocforusedindex_t;
#define PARAMIOCGETUSEDINDEX _PARAMIOC(5)
typedef struct paramiocgetusedindex {
const param_t param;
unsigned ret;
} paramiocgetusedindex_t;
#define PARAMIOCUNSAVED _PARAMIOC(6)
typedef struct paramiocunsaved {
const param_t param;
bool ret;
} paramiocunsaved_t;
#define PARAMIOCGET _PARAMIOC(7)
typedef struct paramiocget {
const param_t param;
const bool deflt;
void *const val;
int ret;
} paramiocget_t;
#define PARAMIOCAUTOSAVE _PARAMIOC(8)
typedef struct paramiocautosave {
const bool enable;
} paramiocautosave_t;
#define PARAMIOCSET _PARAMIOC(9)
typedef struct paramiocset {
const param_t param;
const bool notification;
const void *val;
int ret;
} paramiocset_t;
#define PARAMIOCUSED _PARAMIOC(10)
typedef struct paramiocused {
const param_t param;
bool ret;
} paramiocused_t;
#define PARAMIOCSETUSED _PARAMIOC(11)
typedef struct paramiocsetused {
const param_t param;
} paramiocsetused_t;
#define PARAMIOCSETDEFAULT _PARAMIOC(12)
typedef struct paramiocsetdefault {
const param_t param;
const void *val;
int ret;
} paramiocsetdefault_t;
#define PARAMIOCRESET _PARAMIOC(13)
typedef struct paramiocreset {
const param_t param;
const bool notification;
int ret;
} paramiocreset_t;
#define PARAMIOCRESETGROUP _PARAMIOC(14)
typedef enum {
PARAM_RESET_ALL,
PARAM_RESET_EXCLUDES,
PARAM_RESET_SPECIFIC
} param_reset_type_t;
typedef struct paramiocresetgroup {
param_reset_type_t type;
const char **group;
const int num_in_group;
} paramiocresetgroup_t;
#define PARAMIOCSAVEDEFAULT _PARAMIOC(15)
typedef struct paramiocsavedefault {
int ret;
} paramiocsavedefault_t;
#define PARAMIOCLOADDEFAULT _PARAMIOC(16)
typedef struct paramiocloaddefault {
int ret;
} paramiocloaddefault_t;
#define PARAMIOCEXPORT _PARAMIOC(17)
typedef struct paramiocexport {
const char *filename;
int ret;
} paramiocexport_t;
#define PARAMIOCHASH _PARAMIOC(18)
typedef struct paramiochash {
uint32_t ret;
} paramiochash_t;
int param_ioctl(unsigned int cmd, unsigned long arg);
+1 -1
View File
@@ -33,5 +33,5 @@
add_library(tinybson tinybson.cpp)
target_compile_definitions(tinybson PRIVATE -DMODULE_NAME="tinybson")
target_compile_options(tinybson PRIVATE -Wno-sign-compare) # TODO: fix this
target_compile_options(tinybson PRIVATE ${MAX_CUSTOM_OPT_LEVEL} -Wno-sign-compare) # TODO: fix this
add_dependencies(tinybson prebuild_targets)
+5 -3
View File
@@ -115,10 +115,11 @@ read_double(bson_decoder_t decoder, double *d)
}
int
bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback)
bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback, void *priv)
{
decoder->fd = fd;
decoder->callback = callback;
decoder->priv = priv;
decoder->nesting = 1;
decoder->node.type = BSON_UNDEFINED;
@@ -134,7 +135,7 @@ bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback cal
}
int
bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback)
bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback, void *priv)
{
/* argument sanity */
if ((buf == nullptr) || (callback == nullptr)) {
@@ -155,6 +156,7 @@ bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_
decoder->bufpos = 0;
decoder->callback = callback;
decoder->priv = priv;
decoder->nesting = 1;
decoder->pending = 0;
decoder->node.type = BSON_UNDEFINED;
@@ -315,7 +317,7 @@ bson_decoder_next(bson_decoder_t decoder)
}
/* call the callback and pass its results back */
return decoder->callback(decoder, &decoder->node);
return decoder->callback(decoder, decoder->priv, &decoder->node);
}
int
+7 -3
View File
@@ -101,7 +101,7 @@ typedef struct bson_decoder_s *bson_decoder_t;
*
* The node callback function's return value is returned by bson_decoder_next.
*/
typedef int (* bson_decoder_callback)(bson_decoder_t decoder, bson_node_t node);
typedef int (* bson_decoder_callback)(bson_decoder_t decoder, void *priv, bson_node_t node);
struct bson_decoder_s {
/* file reader state */
@@ -114,6 +114,7 @@ struct bson_decoder_s {
bool dead{false};
bson_decoder_callback callback;
void *priv{nullptr};
unsigned nesting{0};
struct bson_node_s node {};
int32_t pending{0};
@@ -135,9 +136,10 @@ struct bson_decoder_s {
* @param decoder Decoder state structure to be initialised.
* @param fd File to read BSON data from.
* @param callback Callback to be invoked by bson_decoder_next
* @param priv Callback private data, stored in node.
* @return Zero on success.
*/
__EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback);
__EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder_callback callback, void *priv);
/**
* Initialise the decoder to read from a buffer in memory.
@@ -148,9 +150,11 @@ __EXPORT int bson_decoder_init_file(bson_decoder_t decoder, int fd, bson_decoder
* passed as zero if the buffer size should be extracted from the
* BSON header only.
* @param callback Callback to be invoked by bson_decoder_next
* @param priv Callback private data, stored in node.
* @return Zero on success.
*/
__EXPORT int bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback);
__EXPORT int bson_decoder_init_buf(bson_decoder_t decoder, void *buf, unsigned bufsize, bson_decoder_callback callback,
void *priv);
/**
* Process the next node from the stream and invoke the callback.
-221
View File
@@ -1,221 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 Technology Innovation Institute. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file usr_parameters_if.cpp
*
* Protected build user space interface to global parameter store.
*/
#define PARAM_IMPLEMENTATION
#include "param.h"
#include "parameters_ioctl.h"
#include <parameters/px4_parameters.hpp>
#include <sys/boardctl.h>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/log.h>
#include "parameters_common.cpp"
void
param_notify_changes()
{
boardctl(PARAMIOCNOTIFY, NULL);
}
param_t param_find(const char *name)
{
paramiocfind_t data = {name, true, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_find_no_notification(const char *name)
{
paramiocfind_t data = {name, false, PARAM_INVALID};
boardctl(PARAMIOCFIND, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
unsigned param_count_used()
{
paramioccountused_t data = {0};
boardctl(PARAMIOCCOUNTUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
param_t param_for_used_index(unsigned index)
{
paramiocforusedindex_t data = {index, 0};
boardctl(PARAMIOCFORUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_get_used_index(param_t param)
{
paramiocgetusedindex_t data = {param, 0};
boardctl(PARAMIOCGETUSEDINDEX, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool
param_value_unsaved(param_t param)
{
paramiocunsaved_t data = {param, false};
boardctl(PARAMIOCUNSAVED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get(param_t param, void *val)
{
paramiocget_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_get_default_value(param_t param, void *default_val)
{
paramiocget_t data = {param, true, default_val, PX4_ERROR};
boardctl(PARAMIOCGET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_control_autosave(bool enable)
{
paramiocautosave_t data = {enable};
boardctl(PARAMIOCAUTOSAVE, reinterpret_cast<unsigned long>(&data));
}
int param_set(param_t param, const void *val)
{
paramiocset_t data = {param, true, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_set_no_notification(param_t param, const void *val)
{
paramiocset_t data = {param, false, val, PX4_ERROR};
boardctl(PARAMIOCSET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
bool param_used(param_t param)
{
paramiocused_t data = {param, false};
boardctl(PARAMIOCUSED, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void param_set_used(param_t param)
{
paramiocsetused_t data = {param};
boardctl(PARAMIOCSETUSED, reinterpret_cast<unsigned long>(&data));
}
int param_set_default_value(param_t param, const void *val)
{
paramiocsetdefault_t data = {param, val, PX4_ERROR};
boardctl(PARAMIOCSETDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset(param_t param)
{
paramiocreset_t data = {param, true, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int param_reset_no_notification(param_t param)
{
paramiocreset_t data = {param, false, PX4_ERROR};
boardctl(PARAMIOCRESET, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
void
param_reset_all()
{
paramiocresetgroup_t data = {PARAM_RESET_ALL, nullptr, 0};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_excludes(const char *excludes[], int num_excludes)
{
paramiocresetgroup_t data = {PARAM_RESET_EXCLUDES, excludes, num_excludes};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
void
param_reset_specific(const char *resets[], int num_resets)
{
paramiocresetgroup_t data = {PARAM_RESET_SPECIFIC, resets, num_resets};
boardctl(PARAMIOCRESETGROUP, reinterpret_cast<unsigned long>(&data));
}
int param_save_default()
{
paramiocsavedefault_t data = {PX4_ERROR};
boardctl(PARAMIOCSAVEDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_load_default()
{
paramiocloaddefault_t data = {PX4_ERROR};
boardctl(PARAMIOCLOADDEFAULT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
int
param_export(const char *filename, param_filter_func filter)
{
paramiocexport_t data = {filename, PX4_ERROR};
if (filter) { PX4_ERR("ERROR: filter not supported in userside blob"); }
boardctl(PARAMIOCEXPORT, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
uint32_t param_hash_check()
{
paramiochash_t data = {0};
boardctl(PARAMIOCHASH, reinterpret_cast<unsigned long>(&data));
return data.ret;
}
+49 -55
View File
@@ -68,6 +68,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
if (req_list.target_system == mavlink_system.sysid &&
(req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
if (_send_all_index < 0) {
_send_all_index = PARAM_HASH;
@@ -77,15 +78,16 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
}
}
if (req_list.target_system == mavlink_system.sysid && req_list.target_component < 127 &&
if ((req_list.target_system == mavlink_system.sysid) && (req_list.target_component < 127) &&
(req_list.target_component != mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) {
// publish list request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
req.message_type = msg->msgid;
req.node_id = req_list.target_component;
req.param_index = 0;
req.timestamp = hrt_absolute_time();
_uavcan_parameter_request_pub.publish(req);
parameter_request_s parameter_request{};
parameter_request.message_type = parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST;
parameter_request.node_id = req_list.target_component;
parameter_request.param_index = 0;
parameter_request.timestamp = hrt_absolute_time();
_uavcan_parameter_request_pub.publish(parameter_request);
}
break;
@@ -102,8 +104,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
/* local name buffer to enforce null-terminated string */
char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1];
strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
/* enforce null termination */
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; // enforce null termination
/* Whatever the value is, we're being told to stop sending */
if (strncmp(name, "_HASH_CHECK", sizeof(name)) == 0) {
@@ -112,18 +113,20 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
_send_all_index = -1;
}
/* No other action taken, return */
// No other action taken, return
return;
}
/* attempt to find parameter, set and send it */
// attempt to find parameter, set and send it
param_t param = param_find_no_notification(name);
if (param == PARAM_INVALID) {
PX4_ERR("unknown param: %s", name);
} else if (!((param_type(param) == PARAM_TYPE_INT32 && set.param_type == MAV_PARAM_TYPE_INT32) ||
(param_type(param) == PARAM_TYPE_FLOAT && set.param_type == MAV_PARAM_TYPE_REAL32))) {
(param_type(param) == PARAM_TYPE_FLOAT && set.param_type == MAV_PARAM_TYPE_REAL32))
) {
PX4_ERR("param types mismatch param: %s", name);
} else {
@@ -135,27 +138,29 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
if (set.target_system == mavlink_system.sysid && set.target_component < 127 &&
(set.target_component != mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
req.message_type = msg->msgid;
req.node_id = set.target_component;
req.param_index = -1;
strncpy(req.param_id, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1);
req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
parameter_request_s parameter_request{};
parameter_request.message_type = parameter_request_s::MESSAGE_TYPE_PARAM_SET;
parameter_request.node_id = set.target_component;
parameter_request.param_index = -1;
strncpy(parameter_request.name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1);
parameter_request.name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
if (set.param_type == MAV_PARAM_TYPE_REAL32) {
req.param_type = MAV_PARAM_TYPE_REAL32;
req.real_value = set.param_value;
parameter_request.type = parameter_request_s::TYPE_FLOAT32;
parameter_request.float64_value = set.param_value;
} else {
int32_t val;
memcpy(&val, &set.param_value, sizeof(int32_t));
req.param_type = MAV_PARAM_TYPE_INT64;
req.int_value = val;
parameter_request.type = parameter_request_s::TYPE_INT64;
parameter_request.int64_value = val;
}
req.timestamp = hrt_absolute_time();
_uavcan_parameter_request_pub.publish(req);
parameter_request.timestamp = hrt_absolute_time();
_uavcan_parameter_request_pub.publish(parameter_request);
}
break;
@@ -177,7 +182,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
uint32_t hash = param_hash_check();
/* build the one-off response message */
mavlink_param_value_t param_value;
mavlink_param_value_t param_value{};
param_value.param_count = param_count_used();
param_value.param_index = -1;
strncpy(param_value.param_id, HASH_PARAM, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
@@ -210,17 +215,18 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
if (req_read.target_system == mavlink_system.sysid && req_read.target_component < 127 &&
(req_read.target_component != mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) {
// publish set request to UAVCAN driver via uORB.
uavcan_parameter_request_s req{};
req.timestamp = hrt_absolute_time();
req.message_type = msg->msgid;
req.node_id = req_read.target_component;
req.param_index = req_read.param_index;
strncpy(req.param_id, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1);
req.param_id[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
parameter_request_s parameter_request{};
parameter_request.timestamp = hrt_absolute_time();
parameter_request.message_type = parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ;
parameter_request.node_id = req_read.target_component;
parameter_request.param_index = req_read.param_index;
strncpy(parameter_request.name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1);
parameter_request.name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0';
// Enque the request and forward the first to the uavcan node
enque_uavcan_request(&req);
enque_uavcan_request(&parameter_request);
request_next_uavcan_parameter();
}
@@ -397,7 +403,7 @@ bool
MavlinkParametersManager::send_uavcan()
{
/* Send parameter values received from the UAVCAN topic */
uavcan_parameter_value_s value{};
parameter_value_s value;
if (_uavcan_parameter_value_sub.update(&value)) {
@@ -413,9 +419,7 @@ MavlinkParametersManager::send_uavcan()
mavlink_param_value_t msg{};
msg.param_count = value.param_count;
msg.param_index = value.param_index;
#if defined(__GNUC__) && __GNUC__ >= 8
#pragma GCC diagnostic ignored "-Wstringop-truncation"
#endif
/*
* coverity[buffer_size_warning : FALSE]
*
@@ -423,17 +427,14 @@ MavlinkParametersManager::send_uavcan()
* has length 16. In this case the receiving end needs to terminate it
* when copying it.
*/
strncpy(msg.param_id, value.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
#if defined(__GNUC__) && __GNUC__ >= 8
#pragma GCC diagnostic pop
#endif
memcpy(msg.param_id, value.param_name, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
if (value.param_type == MAV_PARAM_TYPE_REAL32) {
if (value.type == parameter_request_s::TYPE_FLOAT32) {
msg.param_type = MAVLINK_TYPE_FLOAT;
msg.param_value = value.real_value;
msg.param_value = value.float64_value;
} else {
int32_t val = (int32_t)value.int_value;
int32_t val = value.int64_value;
memcpy(&msg.param_value, &val, sizeof(int32_t));
msg.param_type = MAVLINK_TYPE_INT32_T;
}
@@ -516,7 +517,7 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
return 1;
}
mavlink_param_value_t msg;
mavlink_param_value_t msg{};
/*
* get param value, since MAVLink encodes float and int params in the same
@@ -544,10 +545,6 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
msg.param_count = param_count_used();
msg.param_index = param_get_used_index(param);
#if defined(__GNUC__) && __GNUC__ >= 8
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wstringop-truncation"
#endif
/*
* coverity[buffer_size_warning : FALSE]
*
@@ -555,10 +552,7 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
* has length 16. In this case the receiving end needs to terminate it
* when copying it.
*/
strncpy(msg.param_id, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
#if defined(__GNUC__) && __GNUC__ >= 8
#pragma GCC diagnostic pop
#endif
memcpy(msg.param_id, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN);
/* query parameter type */
param_type_t type = param_type(param);
@@ -595,7 +589,7 @@ void MavlinkParametersManager::request_next_uavcan_parameter()
{
// Request a parameter if we are not already waiting on a response and if the list is not empty
if (!_uavcan_waiting_for_request_response && _uavcan_open_request_list != nullptr) {
uavcan_parameter_request_s req = _uavcan_open_request_list->req;
parameter_request_s req = _uavcan_open_request_list->req;
_uavcan_parameter_request_pub.publish(req);
@@ -603,7 +597,7 @@ void MavlinkParametersManager::request_next_uavcan_parameter()
}
}
void MavlinkParametersManager::enque_uavcan_request(uavcan_parameter_request_s *req)
void MavlinkParametersManager::enque_uavcan_request(parameter_request_s *req)
{
// We store at max 10 requests to keep memory consumption low.
// Dropped requests will be repeated by the ground station
+6 -22
View File
@@ -49,8 +49,8 @@
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/rc_parameter_map.h>
#include <uORB/topics/uavcan_parameter_request.h>
#include <uORB/topics/uavcan_parameter_value.h>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/parameter_update.h>
#include <drivers/drv_hrt.h>
@@ -105,8 +105,8 @@ protected:
// Item of a single-linked list to store requested uavcan parameters
struct _uavcan_open_request_list_item {
uavcan_parameter_request_s req;
struct _uavcan_open_request_list_item *next;
parameter_request_s req{};
_uavcan_open_request_list_item *next{nullptr};
};
/**
@@ -117,7 +117,7 @@ protected:
/**
* Enqueue one uavcan parameter reqest. We store 10 at max.
*/
void enque_uavcan_request(uavcan_parameter_request_s *req);
void enque_uavcan_request(parameter_request_s *req);
/**
* Drop the first reqest from the list
@@ -131,23 +131,7 @@ protected:
uORB::Publication<rc_parameter_map_s> _rc_param_map_pub{ORB_ID(rc_parameter_map)};
rc_parameter_map_s _rc_param_map{};
uORB::Publication<uavcan_parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};
// enforce ORB_ID(uavcan_parameter_request) constants that map to MAVLINK defines
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ == MAVLINK_MSG_ID_PARAM_REQUEST_READ,
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_READ constant mismatch");
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_SET == MAVLINK_MSG_ID_PARAM_SET,
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_SET constant mismatch");
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST == MAVLINK_MSG_ID_PARAM_REQUEST_LIST,
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_LIST constant mismatch");
static_assert(uavcan_parameter_request_s::NODE_ID_ALL == MAV_COMP_ID_ALL,
"uavcan_parameter_request_s MAV_COMP_ID_ALL constant mismatch");
static_assert(uavcan_parameter_request_s::PARAM_TYPE_UINT8 == MAV_PARAM_TYPE_UINT8,
"uavcan_parameter_request_s MAV_PARAM_TYPE_UINT8 constant mismatch");
static_assert(uavcan_parameter_request_s::PARAM_TYPE_REAL32 == MAV_PARAM_TYPE_REAL32,
"uavcan_parameter_request_s MAV_PARAM_TYPE_REAL32 constant mismatch");
static_assert(uavcan_parameter_request_s::PARAM_TYPE_INT64 == MAV_PARAM_TYPE_INT64,
"uavcan_parameter_request_s MAV_PARAM_TYPE_INT64 constant mismatch");
uORB::Publication<parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};
uORB::Subscription _uavcan_parameter_value_sub{ORB_ID(uavcan_parameter_value)};
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
+2 -2
View File
@@ -96,7 +96,7 @@ encode(bson_encoder_t encoder)
}
static int
decode_callback(bson_decoder_t decoder, bson_node_t node)
decode_callback(bson_decoder_t decoder, void *priv, bson_node_t node)
{
unsigned len;
@@ -287,7 +287,7 @@ test_bson(int argc, char *argv[])
}
/* now test-decode it */
if (bson_decoder_init_buf(&decoder, buf, len, decode_callback)) {
if (bson_decoder_init_buf(&decoder, buf, len, decode_callback, nullptr)) {
PX4_ERR("FAIL: bson_decoder_init_buf");
return 1;
}