mirror of https://github.com/ArduPilot/ardupilot
AP_Param: added AP_PARAM_NO_SHIFT
used for cases where we know the shift is not needed
This commit is contained in:
parent
1d42b0281a
commit
018c7425a4
|
@ -114,7 +114,7 @@ void AP_Param::erase_all(void)
|
|||
*/
|
||||
uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint8_t base, uint8_t i, uint8_t shift)
|
||||
{
|
||||
if (grpinfo[i].idx == 0 && shift != 0) {
|
||||
if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_NO_SHIFT)) {
|
||||
/*
|
||||
this is a special case for a bug in the original design. An
|
||||
idx of 0 shifted by n bits is still zero, which makes it
|
||||
|
|
|
@ -46,6 +46,10 @@
|
|||
// invisible
|
||||
#define AP_PARAM_FLAG_ENABLE 4
|
||||
|
||||
// don't shift index 0 to index 63. Use this when you know there will be
|
||||
// no conflict with the parent
|
||||
#define AP_PARAM_NO_SHIFT 8
|
||||
|
||||
// a variant of offsetof() to work around C++ restrictions.
|
||||
// this can only be used when the offset of a variable in a object
|
||||
// is constant and known at compile time
|
||||
|
|
Loading…
Reference in New Issue