Compare commits

...

4 Commits

Author SHA1 Message Date
Daniel Agar a749c787ca mavlink: param_get proper type to silence errors 2021-11-19 15:55:11 -05:00
Daniel Agar e997a5f384 param.h type checking more info 2021-11-19 15:51:55 -05:00
Daniel Agar 3f5b7d9e36 mavlink: receiver fix SENS_FLOW_ROT type 2021-11-19 15:51:55 -05:00
Daniel Agar c2bc77b9b8 [DO NOT MERGE] testing param types 2021-11-19 15:51:55 -05:00
3 changed files with 26 additions and 9 deletions
+8 -2
View File
@@ -446,12 +446,18 @@ __END_DECLS
#if defined(__cplusplus) && !defined(PARAM_IMPLEMENTATION)
#if 0 // set to 1 to debug param type mismatches
#if 1 // set to 1 to debug param type mismatches
#include <cstdio>
#include <px4_platform_common/log.h>
#ifndef MODULE_NAME
#define MODULE_NAME "px4"
#endif
#define CHECK_PARAM_TYPE(param, type) \
if (param_type(param) != type) { \
/* use printf() to avoid having to use more includes */ \
printf("wrong type passed to param_get() for param %s\n", param_name(param)); \
PX4_ERR("wrong type passed to param_get() for param %s", param_name(param)); \
}
#else
#define CHECK_PARAM_TYPE(param, type)
+17 -6
View File
@@ -516,20 +516,31 @@ MavlinkParametersManager::send_param(param_t param, int component_id)
return 1;
}
mavlink_param_value_t msg;
mavlink_param_value_t msg{};
/*
* get param value, since MAVLink encodes float and int params in the same
* space during transmission, copy param onto float val_buf
*/
float param_value{};
if (param_type(param) == PARAM_TYPE_INT32) {
int32_t param_value;
if (param_get(param, &param_value) != OK) {
return 2;
if (param_get(param, &param_value) != OK) {
return 2;
}
memcpy(&msg.param_value, &param_value, sizeof(param_value));
} else {
float param_value;
if (param_get(param, &param_value) != OK) {
return 2;
}
msg.param_value = param_value;
}
msg.param_value = param_value;
msg.param_count = param_count_used();
msg.param_index = param_get_used_index(param);
+1 -1
View File
@@ -396,7 +396,7 @@ private:
float _param_sens_flow_maxhgt{-1.0f};
float _param_sens_flow_maxr{-1.0f};
float _param_sens_flow_minhgt{-1.0f};
float _param_sens_flow_rot{-1.0f};
int32_t _param_sens_flow_rot{0};
DEFINE_PARAMETERS(
(ParamFloat<px4::params::BAT_CRIT_THR>) _param_bat_crit_thr,