Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

param_server: implemented change_param_? functions #2085

Open
wants to merge 1 commit into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions examples/autopilot_server/autopilot_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
#include <thread>

#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
#include <mavsdk/plugins/telemetry/telemetry.h>
#include <mavsdk/plugins/action/action.h>
#include <mavsdk/plugins/param_server/param_server.h>
Expand Down Expand Up @@ -83,7 +82,8 @@ int main(int argc, char** argv)
paramServer.provide_param_int("SYS_HITL", 0);
paramServer.provide_param_int("MIS_TAKEOFF_ALT", 0);
// Add a custom param
paramServer.provide_param_int("my_param", 1);
paramServer.provide_param_int("MY_PARAM", 1);
paramServer.change_param_int("MY_PARAM", 2);

// Allow the vehicle to change modes, takeoff and arm
actionServer.set_allowable_flight_modes({true, true, true});
Expand Down
2 changes: 1 addition & 1 deletion proto
65 changes: 65 additions & 0 deletions src/mavsdk/core/mavlink_parameter_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,71 @@ MavlinkParameterServer::retrieve_server_param_int(const std::string& name)
return retrieve_server_param<int32_t>(name);
}

MavlinkParameterServer::Result
MavlinkParameterServer::change_server_param(const std::string& name, const ParamValue& param_value)
{
if (name.size() > PARAM_ID_LEN) {
LogErr() << "Error: param name too long";
return Result::ParamNameTooLong;
}
const auto param_opt = _param_cache.param_by_id(name, true);
if (!param_opt.has_value()) {
return Result::NotFound;
}
// This parameter exists, check its type
const auto& param = param_opt.value();
if (!param.value.is_same_type(param_value)) {
return Result::WrongType;
}

if (param_value.is<std::string>()) {
const auto s = param_value.get<std::string>();
if (s.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
LogErr() << "Error: param value too long";
return Result::ParamValueTooLong;
}
}
std::lock_guard<std::mutex> lock(_all_params_mutex);
// then, to not change the public api behaviour, try updating its value.
switch (_param_cache.update_existing_param(name, param_value)) {
case MavlinkParameterCache::UpdateExistingParamResult::Ok:
return Result::Success;
case MavlinkParameterCache::UpdateExistingParamResult::MissingParam:
return Result::ParamNotFound;
case MavlinkParameterCache::UpdateExistingParamResult::WrongType:
return Result::WrongType;
default:
LogErr() << "Unknown update_existing_param result";
assert(false);
}

return Result::Unknown;
}

MavlinkParameterServer::Result
MavlinkParameterServer::change_server_param_float(const std::string& name, float value)
{
ParamValue param_value;
param_value.set(value);
return change_server_param(name, param_value);
}

MavlinkParameterServer::Result
MavlinkParameterServer::change_server_param_int(const std::string& name, int32_t value)
{
ParamValue param_value;
param_value.set(value);
return change_server_param(name, param_value);
}

MavlinkParameterServer::Result MavlinkParameterServer::change_server_param_custom(
const std::string& name, const std::string& value)
{
ParamValue param_value;
param_value.set(value);
return change_server_param(name, param_value);
}

void MavlinkParameterServer::process_param_set_internally(
const std::string& param_id, const ParamValue& value_to_set, bool extended)
{
Expand Down
5 changes: 5 additions & 0 deletions src/mavsdk/core/mavlink_parameter_server.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,6 +55,11 @@ class MavlinkParameterServer : public MavlinkParameterSubscription {
std::pair<Result, int32_t> retrieve_server_param_int(const std::string& name);
std::pair<Result, std::string> retrieve_server_param_custom(const std::string& name);

Result change_server_param(const std::string& name, const ParamValue& param_value);
Result change_server_param_float(const std::string& name, float value);
Result change_server_param_int(const std::string& name, int32_t value);
Result change_server_param_custom(const std::string& name, const std::string& value);

void do_work();

friend std::ostream& operator<<(std::ostream&, const Result&);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,17 @@ class ParamServer : public ServerPluginBase {
*/
Result provide_param_int(std::string name, int32_t value) const;

/**
* @brief Change an int parameter internally.
*
* If the type is wrong, the result will be `WRONG_TYPE`.
*
* This function is blocking.
*
* @return Result of request.
*/
Result change_param_int(std::string name, int32_t value) const;

/**
* @brief Retrieve a float parameter.
*
Expand All @@ -208,6 +219,17 @@ class ParamServer : public ServerPluginBase {
*/
Result provide_param_float(std::string name, float value) const;

/**
* @brief Change a float parameter internally.
*
* If the type is wrong, the result will be `WRONG_TYPE`.
*
* This function is blocking.
*
* @return Result of request.
*/
Result change_param_float(std::string name, float value) const;

/**
* @brief Retrieve a custom parameter.
*
Expand All @@ -230,6 +252,17 @@ class ParamServer : public ServerPluginBase {
*/
Result provide_param_custom(std::string name, std::string value) const;

/**
* @brief Change a custom parameter internally.
*
* If the type is wrong, the result will be `WRONG_TYPE`.
*
* This function is blocking.
*
* @return Result of request.
*/
Result change_param_custom(std::string name, std::string value) const;

/**
* @brief Retrieve all parameters.
*
Expand Down
15 changes: 15 additions & 0 deletions src/mavsdk/plugins/param_server/param_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,11 @@ ParamServer::Result ParamServer::provide_param_int(std::string name, int32_t val
return _impl->provide_param_int(name, value);
}

ParamServer::Result ParamServer::change_param_int(std::string name, int32_t value) const
{
return _impl->change_param_int(name, value);
}

std::pair<ParamServer::Result, float> ParamServer::retrieve_param_float(std::string name) const
{
return _impl->retrieve_param_float(name);
Expand All @@ -41,6 +46,11 @@ ParamServer::Result ParamServer::provide_param_float(std::string name, float val
return _impl->provide_param_float(name, value);
}

ParamServer::Result ParamServer::change_param_float(std::string name, float value) const
{
return _impl->change_param_float(name, value);
}

std::pair<ParamServer::Result, std::string>
ParamServer::retrieve_param_custom(std::string name) const
{
Expand All @@ -52,6 +62,11 @@ ParamServer::Result ParamServer::provide_param_custom(std::string name, std::str
return _impl->provide_param_custom(name, value);
}

ParamServer::Result ParamServer::change_param_custom(std::string name, std::string value) const
{
return _impl->change_param_custom(name, value);
}

ParamServer::AllParams ParamServer::retrieve_all_params() const
{
return _impl->retrieve_all_params();
Expand Down
48 changes: 48 additions & 0 deletions src/mavsdk/plugins/param_server/param_server_impl.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,22 @@ ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t
return ParamServer::Result::Success;
}

ParamServer::Result ParamServerImpl::change_param_int(std::string name, int32_t value)
{
if (name.size() > 16) {
return ParamServer::Result::ParamNameTooLong;
}

const auto result =
_server_component_impl->mavlink_parameter_server().change_server_param_int(name, value);

if (result == MavlinkParameterServer::Result::Success) {
return ParamServer::Result::Success;
} else {
return ParamServer::Result::NotFound;
}
}

std::pair<ParamServer::Result, float> ParamServerImpl::retrieve_param_float(std::string name) const
{
const auto result =
Expand All @@ -60,6 +76,22 @@ ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float
return ParamServer::Result::Success;
}

ParamServer::Result ParamServerImpl::change_param_float(std::string name, float value)
{
if (name.size() > 16) {
return ParamServer::Result::ParamNameTooLong;
}

const auto result =
_server_component_impl->mavlink_parameter_server().change_server_param_float(name, value);

if (result == MavlinkParameterServer::Result::Success) {
return ParamServer::Result::Success;
} else {
return ParamServer::Result::NotFound;
}
}

std::pair<ParamServer::Result, std::string>
ParamServerImpl::retrieve_param_custom(std::string name) const
{
Expand All @@ -83,6 +115,22 @@ ParamServerImpl::provide_param_custom(std::string name, const std::string& value
return ParamServer::Result::Success;
}

ParamServer::Result ParamServerImpl::change_param_custom(std::string name, const std::string& value)
{
if (name.size() > 16) {
return ParamServer::Result::ParamNameTooLong;
}

const auto result =
_server_component_impl->mavlink_parameter_server().change_server_param_custom(name, value);

if (result == MavlinkParameterServer::Result::Success) {
return ParamServer::Result::Success;
} else {
return ParamServer::Result::NotFound;
}
}

ParamServer::AllParams ParamServerImpl::retrieve_all_params() const
{
auto tmp = _server_component_impl->mavlink_parameter_server().retrieve_all_server_params();
Expand Down
6 changes: 6 additions & 0 deletions src/mavsdk/plugins/param_server/param_server_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,14 +18,20 @@ class ParamServerImpl : public ServerPluginImplBase {

ParamServer::Result provide_param_int(std::string name, int32_t value);

ParamServer::Result change_param_int(std::string name, int32_t value);

std::pair<ParamServer::Result, float> retrieve_param_float(std::string name) const;

ParamServer::Result provide_param_float(std::string name, float value);

ParamServer::Result change_param_float(std::string name, float value);

std::pair<ParamServer::Result, std::string> retrieve_param_custom(std::string name) const;

ParamServer::Result provide_param_custom(std::string name, const std::string& value);

ParamServer::Result change_param_custom(std::string name, const std::string& value);

ParamServer::AllParams retrieve_all_params() const;

static ParamServer::Result
Expand Down
Loading