mirror of https://github.com/ArduPilot/ardupilot
AP_Param: add _FLAG to AP_PARAM_NO_SHIFT
Just for consistency with the other flags
This commit is contained in:
parent
7a2a60e65c
commit
840c386a33
|
@ -80,7 +80,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
|
|||
// @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1,
|
||||
AP_PARAM_NO_SHIFT,
|
||||
AP_PARAM_FLAG_NO_SHIFT,
|
||||
AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
|
||||
|
||||
// 2 was the CHECK paramter stored in a AP_Int16
|
||||
|
|
|
@ -158,7 +158,7 @@ void AP_Param::erase_all(void)
|
|||
*/
|
||||
uint32_t AP_Param::group_id(const struct GroupInfo *grpinfo, uint32_t base, uint8_t i, uint8_t shift)
|
||||
{
|
||||
if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_NO_SHIFT)) {
|
||||
if (grpinfo[i].idx == 0 && shift != 0 && !(grpinfo[i].flags & AP_PARAM_FLAG_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
|
||||
|
|
|
@ -62,7 +62,7 @@
|
|||
|
||||
// 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 (1<<3)
|
||||
#define AP_PARAM_FLAG_NO_SHIFT (1<<3)
|
||||
|
||||
// the var_info is a pointer, allowing for dynamic definition of the var_info tree
|
||||
#define AP_PARAM_FLAG_INFO_POINTER (1<<4)
|
||||
|
|
Loading…
Reference in New Issue