mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: move gripper up to AP_Vehicle
also make the singleton return a reference rather than a pointer
This commit is contained in:
parent
362867415f
commit
f3b9304d80
|
@ -1129,20 +1129,17 @@ void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag)
|
|||
#if AP_GRIPPER_ENABLED
|
||||
void RC_Channel::do_aux_function_gripper(const AuxSwitchPos ch_flag)
|
||||
{
|
||||
AP_Gripper *gripper = AP::gripper();
|
||||
if (gripper == nullptr) {
|
||||
return;
|
||||
}
|
||||
AP_Gripper &gripper = AP::gripper();
|
||||
|
||||
switch (ch_flag) {
|
||||
case AuxSwitchPos::LOW:
|
||||
gripper->release();
|
||||
gripper.release();
|
||||
break;
|
||||
case AuxSwitchPos::MIDDLE:
|
||||
// nothing
|
||||
break;
|
||||
case AuxSwitchPos::HIGH:
|
||||
gripper->grab();
|
||||
gripper.grab();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue