Skip to content

Commit 77fdb0b

Browse files
committed
param_server: implemented change_param_? functions
1 parent 0338c3e commit 77fdb0b

File tree

13 files changed

+5164
-1323
lines changed

13 files changed

+5164
-1323
lines changed

examples/autopilot_server/autopilot_server.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,6 @@
33
#include <thread>
44

55
#include <mavsdk/mavsdk.h>
6-
#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
76
#include <mavsdk/plugins/telemetry/telemetry.h>
87
#include <mavsdk/plugins/action/action.h>
98
#include <mavsdk/plugins/param_server/param_server.h>
@@ -83,7 +82,8 @@ int main(int argc, char** argv)
8382
paramServer.provide_param_int("SYS_HITL", 0);
8483
paramServer.provide_param_int("MIS_TAKEOFF_ALT", 0);
8584
// Add a custom param
86-
paramServer.provide_param_int("my_param", 1);
85+
paramServer.provide_param_int("MY_PARAM", 1);
86+
paramServer.change_param_int("MY_PARAM", 2);
8787

8888
// Allow the vehicle to change modes, takeoff and arm
8989
actionServer.set_allowable_flight_modes({true, true, true});

proto

src/mavsdk/core/mavlink_parameter_server.cpp

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -179,6 +179,71 @@ MavlinkParameterServer::retrieve_server_param_int(const std::string& name)
179179
return retrieve_server_param<int32_t>(name);
180180
}
181181

182+
MavlinkParameterServer::Result
183+
MavlinkParameterServer::change_server_param(const std::string& name, const ParamValue& param_value)
184+
{
185+
if (name.size() > PARAM_ID_LEN) {
186+
LogErr() << "Error: param name too long";
187+
return Result::ParamNameTooLong;
188+
}
189+
const auto param_opt = _param_cache.param_by_id(name, true);
190+
if (!param_opt.has_value()) {
191+
return Result::NotFound;
192+
}
193+
// This parameter exists, check its type
194+
const auto& param = param_opt.value();
195+
if (!param.value.is_same_type(param_value)) {
196+
return Result::WrongType;
197+
}
198+
199+
if (param_value.is<std::string>()) {
200+
const auto s = param_value.get<std::string>();
201+
if (s.size() > sizeof(mavlink_param_ext_set_t::param_value)) {
202+
LogErr() << "Error: param value too long";
203+
return Result::ParamValueTooLong;
204+
}
205+
}
206+
std::lock_guard<std::mutex> lock(_all_params_mutex);
207+
// then, to not change the public api behaviour, try updating its value.
208+
switch (_param_cache.update_existing_param(name, param_value)) {
209+
case MavlinkParameterCache::UpdateExistingParamResult::Ok:
210+
return Result::Success;
211+
case MavlinkParameterCache::UpdateExistingParamResult::MissingParam:
212+
return Result::ParamNotFound;
213+
case MavlinkParameterCache::UpdateExistingParamResult::WrongType:
214+
return Result::WrongType;
215+
default:
216+
LogErr() << "Unknown update_existing_param result";
217+
assert(false);
218+
}
219+
220+
return Result::Unknown;
221+
}
222+
223+
MavlinkParameterServer::Result
224+
MavlinkParameterServer::change_server_param_float(const std::string& name, float value)
225+
{
226+
ParamValue param_value;
227+
param_value.set(value);
228+
return change_server_param(name, param_value);
229+
}
230+
231+
MavlinkParameterServer::Result
232+
MavlinkParameterServer::change_server_param_int(const std::string& name, int32_t value)
233+
{
234+
ParamValue param_value;
235+
param_value.set(value);
236+
return change_server_param(name, param_value);
237+
}
238+
239+
MavlinkParameterServer::Result MavlinkParameterServer::change_server_param_custom(
240+
const std::string& name, const std::string& value)
241+
{
242+
ParamValue param_value;
243+
param_value.set(value);
244+
return change_server_param(name, param_value);
245+
}
246+
182247
void MavlinkParameterServer::process_param_set_internally(
183248
const std::string& param_id, const ParamValue& value_to_set, bool extended)
184249
{

src/mavsdk/core/mavlink_parameter_server.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -55,6 +55,11 @@ class MavlinkParameterServer : public MavlinkParameterSubscription {
5555
std::pair<Result, int32_t> retrieve_server_param_int(const std::string& name);
5656
std::pair<Result, std::string> retrieve_server_param_custom(const std::string& name);
5757

58+
Result change_server_param(const std::string& name, const ParamValue& param_value);
59+
Result change_server_param_float(const std::string& name, float value);
60+
Result change_server_param_int(const std::string& name, int32_t value);
61+
Result change_server_param_custom(const std::string& name, const std::string& value);
62+
5863
void do_work();
5964

6065
friend std::ostream& operator<<(std::ostream&, const Result&);

src/mavsdk/plugins/param_server/include/plugins/param_server/param_server.h

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,17 @@ class ParamServer : public ServerPluginBase {
186186
*/
187187
Result provide_param_int(std::string name, int32_t value) const;
188188

189+
/**
190+
* @brief Change an int parameter internally.
191+
*
192+
* If the type is wrong, the result will be `WRONG_TYPE`.
193+
*
194+
* This function is blocking.
195+
*
196+
* @return Result of request.
197+
*/
198+
Result change_param_int(std::string name, int32_t value) const;
199+
189200
/**
190201
* @brief Retrieve a float parameter.
191202
*
@@ -208,6 +219,17 @@ class ParamServer : public ServerPluginBase {
208219
*/
209220
Result provide_param_float(std::string name, float value) const;
210221

222+
/**
223+
* @brief Change a float parameter internally.
224+
*
225+
* If the type is wrong, the result will be `WRONG_TYPE`.
226+
*
227+
* This function is blocking.
228+
*
229+
* @return Result of request.
230+
*/
231+
Result change_param_float(std::string name, float value) const;
232+
211233
/**
212234
* @brief Retrieve a custom parameter.
213235
*
@@ -230,6 +252,17 @@ class ParamServer : public ServerPluginBase {
230252
*/
231253
Result provide_param_custom(std::string name, std::string value) const;
232254

255+
/**
256+
* @brief Change a custom parameter internally.
257+
*
258+
* If the type is wrong, the result will be `WRONG_TYPE`.
259+
*
260+
* This function is blocking.
261+
*
262+
* @return Result of request.
263+
*/
264+
Result change_param_custom(std::string name, std::string value) const;
265+
233266
/**
234267
* @brief Retrieve all parameters.
235268
*

src/mavsdk/plugins/param_server/param_server.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,11 @@ ParamServer::Result ParamServer::provide_param_int(std::string name, int32_t val
3131
return _impl->provide_param_int(name, value);
3232
}
3333

34+
ParamServer::Result ParamServer::change_param_int(std::string name, int32_t value) const
35+
{
36+
return _impl->change_param_int(name, value);
37+
}
38+
3439
std::pair<ParamServer::Result, float> ParamServer::retrieve_param_float(std::string name) const
3540
{
3641
return _impl->retrieve_param_float(name);
@@ -41,6 +46,11 @@ ParamServer::Result ParamServer::provide_param_float(std::string name, float val
4146
return _impl->provide_param_float(name, value);
4247
}
4348

49+
ParamServer::Result ParamServer::change_param_float(std::string name, float value) const
50+
{
51+
return _impl->change_param_float(name, value);
52+
}
53+
4454
std::pair<ParamServer::Result, std::string>
4555
ParamServer::retrieve_param_custom(std::string name) const
4656
{
@@ -52,6 +62,11 @@ ParamServer::Result ParamServer::provide_param_custom(std::string name, std::str
5262
return _impl->provide_param_custom(name, value);
5363
}
5464

65+
ParamServer::Result ParamServer::change_param_custom(std::string name, std::string value) const
66+
{
67+
return _impl->change_param_custom(name, value);
68+
}
69+
5570
ParamServer::AllParams ParamServer::retrieve_all_params() const
5671
{
5772
return _impl->retrieve_all_params();

src/mavsdk/plugins/param_server/param_server_impl.cpp

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -39,6 +39,22 @@ ParamServer::Result ParamServerImpl::provide_param_int(std::string name, int32_t
3939
return ParamServer::Result::Success;
4040
}
4141

42+
ParamServer::Result ParamServerImpl::change_param_int(std::string name, int32_t value)
43+
{
44+
if (name.size() > 16) {
45+
return ParamServer::Result::ParamNameTooLong;
46+
}
47+
48+
const auto result =
49+
_server_component_impl->mavlink_parameter_server().change_server_param_int(name, value);
50+
51+
if (result == MavlinkParameterServer::Result::Success) {
52+
return ParamServer::Result::Success;
53+
} else {
54+
return ParamServer::Result::NotFound;
55+
}
56+
}
57+
4258
std::pair<ParamServer::Result, float> ParamServerImpl::retrieve_param_float(std::string name) const
4359
{
4460
const auto result =
@@ -60,6 +76,22 @@ ParamServer::Result ParamServerImpl::provide_param_float(std::string name, float
6076
return ParamServer::Result::Success;
6177
}
6278

79+
ParamServer::Result ParamServerImpl::change_param_float(std::string name, float value)
80+
{
81+
if (name.size() > 16) {
82+
return ParamServer::Result::ParamNameTooLong;
83+
}
84+
85+
const auto result =
86+
_server_component_impl->mavlink_parameter_server().change_server_param_float(name, value);
87+
88+
if (result == MavlinkParameterServer::Result::Success) {
89+
return ParamServer::Result::Success;
90+
} else {
91+
return ParamServer::Result::NotFound;
92+
}
93+
}
94+
6395
std::pair<ParamServer::Result, std::string>
6496
ParamServerImpl::retrieve_param_custom(std::string name) const
6597
{
@@ -83,6 +115,22 @@ ParamServerImpl::provide_param_custom(std::string name, const std::string& value
83115
return ParamServer::Result::Success;
84116
}
85117

118+
ParamServer::Result ParamServerImpl::change_param_custom(std::string name, const std::string& value)
119+
{
120+
if (name.size() > 16) {
121+
return ParamServer::Result::ParamNameTooLong;
122+
}
123+
124+
const auto result =
125+
_server_component_impl->mavlink_parameter_server().change_server_param_custom(name, value);
126+
127+
if (result == MavlinkParameterServer::Result::Success) {
128+
return ParamServer::Result::Success;
129+
} else {
130+
return ParamServer::Result::NotFound;
131+
}
132+
}
133+
86134
ParamServer::AllParams ParamServerImpl::retrieve_all_params() const
87135
{
88136
auto tmp = _server_component_impl->mavlink_parameter_server().retrieve_all_server_params();

src/mavsdk/plugins/param_server/param_server_impl.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,14 +18,20 @@ class ParamServerImpl : public ServerPluginImplBase {
1818

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

21+
ParamServer::Result change_param_int(std::string name, int32_t value);
22+
2123
std::pair<ParamServer::Result, float> retrieve_param_float(std::string name) const;
2224

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

27+
ParamServer::Result change_param_float(std::string name, float value);
28+
2529
std::pair<ParamServer::Result, std::string> retrieve_param_custom(std::string name) const;
2630

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

33+
ParamServer::Result change_param_custom(std::string name, const std::string& value);
34+
2935
ParamServer::AllParams retrieve_all_params() const;
3036

3137
static ParamServer::Result

0 commit comments

Comments
 (0)