mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Camera: enable relay off in all builds
This commit is contained in:
parent
960574cccf
commit
6516bffbb6
@ -137,11 +137,9 @@ AP_Camera::trigger_pic_cleanup()
|
|||||||
case AP_CAMERA_TRIGGER_TYPE_WP_DISTANCE:
|
case AP_CAMERA_TRIGGER_TYPE_WP_DISTANCE:
|
||||||
RC_Channel_aux::set_radio(RC_Channel_aux::k_cam_trigger, _servo_off_pwm);
|
RC_Channel_aux::set_radio(RC_Channel_aux::k_cam_trigger, _servo_off_pwm);
|
||||||
break;
|
break;
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
|
||||||
case AP_CAMERA_TRIGGER_TYPE_RELAY:
|
case AP_CAMERA_TRIGGER_TYPE_RELAY:
|
||||||
_apm_relay->off();
|
_apm_relay->off();
|
||||||
break;
|
break;
|
||||||
#endif
|
|
||||||
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
|
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
|
||||||
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN, 0);
|
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN, 0);
|
||||||
break;
|
break;
|
||||||
|
Loading…
Reference in New Issue
Block a user