Compare commits

...

2 Commits

Author SHA1 Message Date
Daniel Agar 58006c0a93 WIP parameter server 2021-04-08 09:31:00 -04:00
Daniel Agar 4e6f366ead WIP: parameter uORB access 2021-04-07 21:41:33 -04:00
12 changed files with 347 additions and 145 deletions

View File

@ -148,8 +148,8 @@ set(msg_files
trajectory_waypoint.msg
transponder_report.msg
tune_control.msg
uavcan_parameter_request.msg
uavcan_parameter_value.msg
parameter_request.msg
parameter_value.msg
ulog_stream.msg
ulog_stream_ack.msg
vehicle_acceleration.msg

26
msg/parameter_request.msg Normal file
View File

@ -0,0 +1,26 @@
# 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 # 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 # parameter name
int16 param_index # -1 if the param_id field should be used as identifier
uint8 TYPE_UINT8 = 1
uint8 TYPE_INT32 = 6
uint8 TYPE_INT64 = 8
uint8 TYPE_REAL32 = 9
uint8 param_type # 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
# TOPICS parameter_request uavcan_parameter_request

View File

@ -1,9 +1,17 @@
# 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
uint8 param_type # parameter type
int64 int_value # current value if param_type is int-like
float32 real_value # current value if param_type is float-like
# TOPICS parameter_value uavcan_parameter_value

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

View File

@ -59,7 +59,7 @@
#include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/uavcan_parameter_request.h>
#include <uORB/topics/parameter_request.h>
/**
* @file uavcan_servers.cpp
@ -326,7 +326,7 @@ UavcanServers::run(pthread_addr_t)
// 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]) {
@ -334,7 +334,7 @@ UavcanServers::run(pthread_addr_t)
* 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) {
@ -354,7 +354,7 @@ UavcanServers::run(pthread_addr_t)
_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) {
@ -364,10 +364,10 @@ UavcanServers::run(pthread_addr_t)
req.name = (char *)request.param_id;
}
if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_REAL32) {
if (request.param_type == parameter_request_s::TYPE_REAL32) {
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.real_value;
} else if (request.param_type == uavcan_parameter_request_s::PARAM_TYPE_UINT8) {
} else if (request.param_type == parameter_request_s::TYPE_UINT8) {
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int_value;
} else {
@ -387,7 +387,7 @@ UavcanServers::run(pthread_addr_t)
_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;
@ -397,8 +397,8 @@ UavcanServers::run(pthread_addr_t)
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.
@ -631,13 +631,13 @@ UavcanServers::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param
} else {
/*
* Currently in parameter get/set mode:
* Publish a uORB uavcan_parameter_value message containing the current value
* Publish a uORB parameter_value message containing the current value
* of the parameter.
*/
if (result.isSuccessful()) {
uavcan::protocol::param::GetSet::Response param = result.getResponse();
struct 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';
@ -645,15 +645,15 @@ UavcanServers::cb_getset(const uavcan::ServiceCallResult<uavcan::protocol::param
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.param_type = parameter_request_s::TYPE_INT64;
response.int_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.param_type = parameter_request_s::TYPE_REAL32;
response.real_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.param_type = parameter_request_s::TYPE_UINT8;
response.int_value = param.value.to<uavcan::protocol::param::Value::Tag::boolean_value>();
}

View File

@ -38,7 +38,7 @@
#include <drivers/device/Device.hpp>
#include <lib/perf/perf_counter.h>
#include <uORB/Publication.hpp>
#include <uORB/topics/uavcan_parameter_value.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/topics/vehicle_command_ack.h>
#include <uavcan/node/sub_node.hpp>
@ -162,7 +162,7 @@ private:
bool _cmd_in_progress = false;
// uORB topic handle for MAVLink parameter responses
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)};
typedef uavcan::MethodBinder<UavcanServers *,

View File

@ -151,6 +151,8 @@ if (NOT "${PX4_BOARD}" MATCHES "px4_io")
add_library(parameters
${SRCS}
px4_parameters.hpp
ParametersServer.cpp
ParametersServer.hpp
)
target_link_libraries(parameters PRIVATE perf tinybson px4_layer)

View File

@ -0,0 +1,187 @@
/****************************************************************************
*
* Copyright (c) 2021 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 "ParametersServer.hpp"
#include <px4_platform_common/atomic.h>
#include "param.h"
static ParametersServer *_param_autosave{nullptr};
float ParametersServer::last_autosave_elapsed() const
{
return hrt_elapsed_time_atomic(&_last_autosave_timestamp) * 1e-6f;
}
void ParametersServer::AutoSave()
{
if (_param_autosave == nullptr) {
return;
}
// wait at least 300ms before saving, because:
// - tasks often call param_set() for multiple params, so this avoids unnecessary save calls
// - the logger stores changed params. He gets notified on a param change via uORB and then
// looks at all unsaved params.
float delay = 0.3f;
static constexpr float rate_limit = 2.0f; // rate-limit saving to 2 seconds
const float last_save_elapsed = _param_autosave->last_autosave_elapsed();
if (last_save_elapsed < rate_limit && rate_limit > last_save_elapsed + delay) {
delay = rate_limit - last_save_elapsed;
}
uint64_t delay_us = delay * 1e6f;
_param_autosave->ScheduleDelayed(delay_us);
}
bool ParametersServer::EnableAutoSave(bool enable)
{
if (enable) {
if (_param_autosave == nullptr) {
_param_autosave = new ParametersServer();
if (_param_autosave == nullptr) {
PX4_ERR("ParametersServer alloc failed");
return false;
}
}
} else {
// TODO: how to prevent delete if currently running?
delete _param_autosave;
_param_autosave = nullptr;
}
return true;
}
void ParametersServer::print_status()
{
if (_param_autosave) {
PX4_INFO("last auto save: %.3f seconds ago", (double)_param_autosave->last_autosave_elapsed());
} else {
PX4_INFO("auto save: off");
}
}
void ParametersServer::Run()
{
_last_autosave_timestamp = hrt_absolute_time();
int ret = param_save_default();
if (ret != 0) {
PX4_ERR("param auto save failed (%i)", ret);
}
// Check for parameter requests (get/set/list)
if (_param_request_sub.updated()) {
parameter_request_s request{};
param_request_sub.copy(&request);
/*
* We know how many parameters are exposed by this node, so
* process the request.
*/
if (request.message_type == parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ) {
parameter_value_s parameter_value{};
if (request.param_index >= 0) {
param_for_index(request.param_index);
} else {
param_find(&request.param_id);
}
int call_res = _param_getset_client.call(request.node_id, req);
if (call_res < 0) {
PX4_ERR("couldn't send GetSet: %d", call_res);
} else {
_param_in_progress = true;
_param_index = request.param_index;
}
} 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;
}
if (request.param_type == parameter_request_s::TYPE_REAL32) {
req.value.to<uavcan::protocol::param::Value::Tag::real_value>() = request.real_value;
} else if (request.param_type == parameter_request_s::TYPE_UINT8) {
req.value.to<uavcan::protocol::param::Value::Tag::boolean_value>() = request.int_value;
} else {
req.value.to<uavcan::protocol::param::Value::Tag::integer_value>() = request.int_value;
}
} 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;
_param_list_node_id = request.node_id;
_param_list_all_nodes = false;
PX4_DEBUG("starting component-specific param 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.
*/
_param_index = 0;
_param_list_in_progress = true;
_param_list_node_id = get_next_active_node_id(0);
_param_list_all_nodes = true;
PX4_DEBUG("starting global param list with node %hhu", _param_list_node_id);
if (_param_counts[_param_list_node_id] == 0) {
param_count(_param_list_node_id);
}
}
}
}
}

View File

@ -0,0 +1,71 @@
/****************************************************************************
*
* Copyright (c) 2021 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_work_queue/ScheduledWorkItem.hpp>
#include <uORB/topics/parameter_request.h>
#include <uORB/topics/parameter_value.h>
#include <uORB/Publication.hpp>
#include <uORB/SubscriptionCallback.hpp>
/**
* 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).
*/
class ParametersServer : public px4::ScheduledWorkItem
{
public:
ParametersServer() : px4::ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) {}
~ParametersServer() override = default;
float last_autosave_elapsed() const;
static void AutoSave();
static bool EnableAutoSave(bool enable = true);
static void print_status();
private:
void Run() override;
hrt_abstime _last_autosave_timestamp{0};
uORB::Publication<parameter_value_s> _param_response_pub{ORB_ID(parameter_value)};
uORB::Subscription _param_request_sub{ORB_ID(uavcan_parameter_request)};
};

View File

@ -89,12 +89,7 @@ static char *param_user_file = nullptr;
#define PARAM_CLOSE close
#endif
#include <px4_platform_common/workqueue.h>
/* autosaving variables */
static hrt_abstime last_autosave_timestamp = 0;
static struct work_s autosave_work {};
static px4::atomic<bool> autosave_scheduled{false};
static bool autosave_disabled = false;
#include "ParametersServer.hpp"
static constexpr uint16_t param_info_count = sizeof(px4::parameters) / sizeof(param_info_s);
static px4::AtomicBitset<param_info_count> params_active; // params found
@ -199,6 +194,8 @@ param_init()
param_find_perf = perf_alloc(PC_COUNT, "param: find");
param_get_perf = perf_alloc(PC_COUNT, "param: get");
param_set_perf = perf_alloc(PC_ELAPSED, "param: set");
param_control_autosave(true);
}
/**
@ -645,44 +642,6 @@ param_get_system_default_value(param_t param, void *default_val)
return ret;
}
/**
* worker callback method to save the parameters
* @param arg unused
*/
static void
autosave_worker(void *arg)
{
bool disabled = false;
if (!param_get_default_file()) {
// In case we save to FLASH, defer param writes until disarmed,
// as writing to FLASH can stall the entire CPU (in rare cases around 300ms on STM32F7)
uORB::SubscriptionData<actuator_armed_s> armed_sub{ORB_ID(actuator_armed)};
if (armed_sub.get().armed) {
work_queue(LPWORK, &autosave_work, (worker_t)&autosave_worker, nullptr, USEC2TICK(1_s));
return;
}
}
param_lock_writer();
last_autosave_timestamp = hrt_absolute_time();
autosave_scheduled.store(false);
disabled = autosave_disabled;
param_unlock_writer();
if (disabled) {
return;
}
PX4_DEBUG("Autosaving params");
int ret = param_save_default();
if (ret != 0) {
PX4_ERR("param auto save failed (%i)", ret);
}
}
/**
* Automatically save the parameters after a timeout and limited rate.
*
@ -692,38 +651,14 @@ autosave_worker(void *arg)
static void
param_autosave()
{
if (autosave_scheduled.load() || autosave_disabled) {
return;
}
// wait at least 300ms before saving, because:
// - tasks often call param_set() for multiple params, so this avoids unnecessary save calls
// - the logger stores changed params. He gets notified on a param change via uORB and then
// looks at all unsaved params.
hrt_abstime delay = 300_ms;
static constexpr const hrt_abstime rate_limit = 2_s; // rate-limit saving to 2 seconds
const hrt_abstime last_save_elapsed = hrt_elapsed_time(&last_autosave_timestamp);
if (last_save_elapsed < rate_limit && rate_limit > last_save_elapsed + delay) {
delay = rate_limit - last_save_elapsed;
}
autosave_scheduled.store(true);
work_queue(LPWORK, &autosave_work, (worker_t)&autosave_worker, nullptr, USEC2TICK(delay));
ParametersServer::AutoSave();
}
void
param_control_autosave(bool enable)
{
param_lock_writer();
if (!enable && autosave_scheduled.load()) {
work_cancel(LPWORK, &autosave_work);
autosave_scheduled.store(false);
}
autosave_disabled = !enable;
ParametersServer::EnableAutoSave(enable);
param_unlock_writer();
}
@ -1527,11 +1462,7 @@ void param_print_status()
param_custom_default_values->n * sizeof(UT_icd));
}
PX4_INFO("auto save: %s", autosave_disabled ? "off" : "on");
if (!autosave_disabled && (last_autosave_timestamp > 0)) {
PX4_INFO("last auto save: %.3f seconds ago", hrt_elapsed_time(&last_autosave_timestamp) * 1e-6);
}
ParametersServer::print_status();
perf_print_counter(param_export_perf);
perf_print_counter(param_find_perf);

View File

@ -80,7 +80,7 @@ MavlinkParametersManager::handle_message(const mavlink_message_t *msg)
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{};
parameter_request_s req{};
req.message_type = msg->msgid;
req.node_id = req_list.target_component;
req.param_index = 0;
@ -140,7 +140,7 @@ 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{};
parameter_request_s req{};
req.message_type = msg->msgid;
req.node_id = set.target_component;
req.param_index = -1;
@ -219,7 +219,7 @@ 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{};
parameter_request_s req{};
req.timestamp = hrt_absolute_time();
req.message_type = msg->msgid;
req.node_id = req_read.target_component;
@ -406,7 +406,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)) {
@ -593,7 +593,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);
@ -601,7 +601,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

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,22 +131,22 @@ 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)};
uORB::Publication<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");
static_assert(parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ == MAVLINK_MSG_ID_PARAM_REQUEST_READ,
"parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_READ constant mismatch");
static_assert(parameter_request_s::MESSAGE_TYPE_PARAM_SET == MAVLINK_MSG_ID_PARAM_SET,
"parameter_request_s MAVLINK_MSG_ID_PARAM_SET constant mismatch");
static_assert(parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_LIST == MAVLINK_MSG_ID_PARAM_REQUEST_LIST,
"parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_LIST constant mismatch");
static_assert(parameter_request_s::NODE_ID_ALL == MAV_COMP_ID_ALL,
"parameter_request_s MAV_COMP_ID_ALL constant mismatch");
static_assert(parameter_request_s::TYPE_UINT8 == MAV_PARAM_TYPE_UINT8,
"parameter_request_s MAV_PARAM_TYPE_UINT8 constant mismatch");
static_assert(parameter_request_s::TYPE_REAL32 == MAV_PARAM_TYPE_REAL32,
"parameter_request_s MAV_PARAM_TYPE_REAL32 constant mismatch");
static_assert(parameter_request_s::TYPE_INT64 == MAV_PARAM_TYPE_INT64,
"parameter_request_s MAV_PARAM_TYPE_INT64 constant mismatch");
uORB::Subscription _uavcan_parameter_value_sub{ORB_ID(uavcan_parameter_value)};