Browse Source

drivers/uavcannode: Add a simple parameter server (simpler version for merging) (#16649)

* drivers/uavcannode: Add a simple parameter server

Added a simple parameter server using the libuavcan ParamServer class.
The parameter server exposes a selection of PX4 parameters via UAVCAN.
Also, Increased the stack size of the uavcan work queue in order to
prevent a stack overflow.

* uavcannode: fetch all active PX4 parameters

Co-authored-by: Kenneth Thompson <ken@flyvoly.com>
release/1.12
Daniel Agar 4 years ago committed by GitHub
parent
commit
e656c9c13f
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 2
      platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp
  2. 4
      src/drivers/uavcannode/CMakeLists.txt
  3. 3
      src/drivers/uavcannode/UavcanNode.cpp
  4. 4
      src/drivers/uavcannode/UavcanNode.hpp
  5. 132
      src/drivers/uavcannode/UavcanNodeParamManager.cpp
  6. 54
      src/drivers/uavcannode/UavcanNodeParamManager.hpp

2
platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp

@ -75,7 +75,7 @@ static constexpr wq_config_t INS3{"wq:INS3", 6000, -17}; @@ -75,7 +75,7 @@ static constexpr wq_config_t INS3{"wq:INS3", 6000, -17};
static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -18};
static constexpr wq_config_t uavcan{"wq:uavcan", 3000, -19};
static constexpr wq_config_t uavcan{"wq:uavcan", 3680, -19};
static constexpr wq_config_t UART0{"wq:UART0", 1400, -21};
static constexpr wq_config_t UART1{"wq:UART1", 1400, -22};

4
src/drivers/uavcannode/CMakeLists.txt

@ -119,12 +119,16 @@ px4_add_module( @@ -119,12 +119,16 @@ px4_add_module(
${LIBUAVCAN_DIR}/libuavcan/include/dsdlc_generated
${LIBUAVCAN_DIR}/libuavcan_drivers/posix/include
${LIBUAVCAN_DIR_DRIVERS}/${UAVCAN_DRIVER}/driver/include
COMPILE_OPTIONS
#-O0
SRCS
allocator.hpp
uavcan_driver.hpp
indication_controller.cpp
UavcanNode.cpp
UavcanNode.hpp
UavcanNodeParamManager.hpp
UavcanNodeParamManager.cpp
DEPENDS
px4_uavcan_dsdlc

3
src/drivers/uavcannode/UavcanNode.cpp

@ -83,6 +83,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys @@ -83,6 +83,7 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys
_raw_air_data_publisher(_node),
_range_sensor_measurement(_node),
_flow_measurement_publisher(_node),
_param_server(_node),
_cycle_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": cycle time")),
_interval_perf(perf_alloc(PC_INTERVAL, MODULE_NAME": cycle interval")),
_reset_timer(_node)
@ -290,6 +291,7 @@ void UavcanNode::Run() @@ -290,6 +291,7 @@ void UavcanNode::Run()
if (!_initialized) {
get_node().setRestartRequestHandler(&restart_request_handler);
_param_server.start(&_param_manager);
init_indication_controller(get_node());
@ -313,6 +315,7 @@ void UavcanNode::Run() @@ -313,6 +315,7 @@ void UavcanNode::Run()
_sensor_baro_sub.registerCallback();
_sensor_gps_sub.registerCallback();
_sensor_mag_sub.registerCallback();
_sensor_gps_sub.registerCallback();
_initialized = true;
}

4
src/drivers/uavcannode/UavcanNode.hpp

@ -48,6 +48,7 @@ @@ -48,6 +48,7 @@
#include "uavcan_driver.hpp"
#include "allocator.hpp"
#include "UavcanNodeParamManager.hpp"
#include <uavcan/helpers/heap_based_pool_allocator.hpp>
#include <uavcan/protocol/global_time_sync_slave.hpp>
@ -200,6 +201,9 @@ private: @@ -200,6 +201,9 @@ private:
uORB::SubscriptionCallbackWorkItem _sensor_mag_sub{this, ORB_ID(sensor_mag)};
uORB::SubscriptionCallbackWorkItem _sensor_gps_sub{this, ORB_ID(sensor_gps)};
UavcanNodeParamManager _param_manager;
uavcan::ParamServer _param_server;
perf_counter_t _cycle_perf;
perf_counter_t _interval_perf;

132
src/drivers/uavcannode/UavcanNodeParamManager.cpp

@ -0,0 +1,132 @@ @@ -0,0 +1,132 @@
/****************************************************************************
*
* 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 "UavcanNodeParamManager.hpp"
#include <px4_platform_common/defines.h>
#include <lib/parameters/param.h>
void UavcanNodeParamManager::getParamNameByIndex(Index index, Name &out_name) const
{
if (index < param_count_used()) {
out_name = param_name(param_for_used_index(index));
}
}
void UavcanNodeParamManager::assignParamValue(const Name &name, const Value &value)
{
param_t param_handle = param_find(name.c_str());
if (param_handle == PARAM_INVALID) {
// Invalid parameter name
return;
}
// Assign input value to parameter if types match
param_type_t value_type = param_type(param_handle);
if (value.is(uavcan::protocol::param::Value::Tag::integer_value) && (value_type == PARAM_TYPE_INT32)) {
auto val = *value.as<uavcan::protocol::param::Value::Tag::integer_value>();
if ((val <= INT32_MAX) || (val >= INT32_MIN)) {
int32_t in_param = val;
param_set(param_handle, &in_param);
}
} else if (value.is(uavcan::protocol::param::Value::Tag::real_value) && (value_type == PARAM_TYPE_FLOAT)) {
// TODO: min/max value checking for float
float in_param = *value.as<uavcan::protocol::param::Value::Tag::real_value>();
param_set(param_handle, &in_param);
}
}
void UavcanNodeParamManager::readParamValue(const Name &name, Value &out_value) const
{
param_t param_handle = param_find(name.c_str());
if (param_handle == PARAM_INVALID) {
// Invalid parameter name
return;
}
// Copy current parameter value to out_value
param_type_t value_type = param_type(param_handle);
if (value_type == PARAM_TYPE_INT32) {
int32_t current_value;
param_get(param_handle, &current_value);
out_value.to<uavcan::protocol::param::Value::Tag::integer_value>() = current_value;
} else if (value_type == PARAM_TYPE_FLOAT) {
float current_value;
param_get(param_handle, &current_value);
out_value.to<uavcan::protocol::param::Value::Tag::real_value>() = current_value;
}
}
void UavcanNodeParamManager::readParamDefaultMaxMin(const Name &name, Value &out_default,
NumericValue &out_max, NumericValue &out_min) const
{
// TODO: get actual default value (will require a new function in param.h)
param_t param_handle = param_find(name.c_str());
if (param_handle == PARAM_INVALID) {
// Invalid parameter name
return;
}
param_type_t value_type = param_type(param_handle);
if (value_type == PARAM_TYPE_INT32) {
out_max.to<uavcan::protocol::param::NumericValue::Tag::integer_value>() = INT32_MAX;
out_min.to<uavcan::protocol::param::NumericValue::Tag::integer_value>() = INT32_MIN;
out_default.to<uavcan::protocol::param::Value::Tag::integer_value>() = 0;
} else if (value_type == PARAM_TYPE_FLOAT) {
out_max.to<uavcan::protocol::param::NumericValue::Tag::real_value>() = FLT_MAX;
out_min.to<uavcan::protocol::param::NumericValue::Tag::real_value>() = -FLT_MAX;
out_default.to<uavcan::protocol::param::Value::Tag::real_value>() = 0.0;
}
}
int UavcanNodeParamManager::saveAllParams()
{
// Nothing to do here assuming autosave is turned on
return 0;
}
int UavcanNodeParamManager::eraseAllParams()
{
param_reset_all();
return 0;
}

54
src/drivers/uavcannode/UavcanNodeParamManager.hpp

@ -0,0 +1,54 @@ @@ -0,0 +1,54 @@
/****************************************************************************
*
* 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 <uavcan/uavcan.hpp>
#include <uavcan/protocol/param_server.hpp>
class UavcanNodeParamManager : public uavcan::IParamManager
{
public:
UavcanNodeParamManager() = default;
void getParamNameByIndex(Index index, Name &out_name) const override;
void assignParamValue(const Name &name, const Value &value) override;
void readParamValue(const Name &name, Value &out_value) const override;
void readParamDefaultMaxMin(const Name &name, Value &out_default,
NumericValue &out_max, NumericValue &out_min) const override;
int saveAllParams() override;
int eraseAllParams() override;
private:
};
Loading…
Cancel
Save