mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: Only use the 6 LSBs, avoids a cpp warning
This commit is contained in:
parent
3aee083540
commit
00d9cc2e09
@ -1241,7 +1241,7 @@ void Copter::convert_lgr_parameters(void)
|
||||
snprintf(pname, sizeof(pname), "SERVO%u_TRIM", chan);
|
||||
servo_trim = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
||||
|
||||
snprintf(pname, sizeof(pname), "SERVO%u_REVERSED", chan & 0x32);
|
||||
snprintf(pname, sizeof(pname), "SERVO%u_REVERSED", chan & 0x3F); // Only use the 6 LSBs, avoids a cpp warning
|
||||
servo_reversed = (AP_Int16 *)AP_Param::find(pname, &ptype);
|
||||
|
||||
if (!servo_min || !servo_max || !servo_trim || !servo_reversed) {
|
||||
|
Loading…
Reference in New Issue
Block a user