mirror of https://github.com/ArduPilot/ardupilot
AP_Param: fixed ARM PX4 build
This commit is contained in:
parent
3ac3aeb1b1
commit
4764a03aaa
|
@ -471,6 +471,10 @@ public:
|
|||
return _value[i];
|
||||
}
|
||||
|
||||
T & operator[](int8_t i) {
|
||||
return _value[(uint8_t)i];
|
||||
}
|
||||
|
||||
/// Value getter
|
||||
///
|
||||
/// @note Returns zero for index values out of range.
|
||||
|
@ -532,11 +536,4 @@ AP_PARAMDEFA(float, Vector6f, 6, AP_PARAM_VECTOR6F);
|
|||
// _pt is the enum ap_var_type type
|
||||
#define AP_PARAMDEFV(_t, _suffix, _pt) typedef AP_ParamV<_t, _pt> AP_ ## _suffix;
|
||||
|
||||
/// Rely on built in casting for other variable types
|
||||
/// to minimize template creation and save memory
|
||||
#define AP_Uint8 AP_Int8
|
||||
#define AP_Uint16 AP_Int16
|
||||
#define AP_Uint32 AP_Int32
|
||||
#define AP_Bool AP_Int8
|
||||
|
||||
#endif // AP_PARAM_H
|
||||
|
|
Loading…
Reference in New Issue