@@ -179,6 +179,71 @@ MavlinkParameterServer::retrieve_server_param_int(const std::string& name)
179
179
return retrieve_server_param<int32_t >(name);
180
180
}
181
181
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
+
182
247
void MavlinkParameterServer::process_param_set_internally (
183
248
const std::string& param_id, const ParamValue& value_to_set, bool extended)
184
249
{
0 commit comments