2023-02-10 20:27:39 -04:00
|
|
|
#include "AP_Camera_Relay.h"
|
|
|
|
|
2023-03-06 19:04:43 -04:00
|
|
|
#if AP_CAMERA_RELAY_ENABLED
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
#include <AP_Relay/AP_Relay.h>
|
|
|
|
|
|
|
|
// update - should be called at 50hz
|
|
|
|
void AP_Camera_Relay::update()
|
|
|
|
{
|
|
|
|
if (trigger_counter > 0) {
|
|
|
|
trigger_counter--;
|
|
|
|
} else {
|
|
|
|
AP_Relay *ap_relay = AP::relay();
|
|
|
|
if (ap_relay == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2023-12-08 00:29:31 -04:00
|
|
|
ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, !_params.relay_on);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// call parent update
|
|
|
|
AP_Camera_Backend::update();
|
|
|
|
}
|
|
|
|
|
|
|
|
// entry point to actually take a picture. returns true on success
|
|
|
|
bool AP_Camera_Relay::trigger_pic()
|
|
|
|
{
|
|
|
|
// fail if have not completed previous picture
|
|
|
|
if (trigger_counter > 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// exit immediately if no relay is setup
|
|
|
|
AP_Relay *ap_relay = AP::relay();
|
|
|
|
if (ap_relay == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2023-12-08 00:29:31 -04:00
|
|
|
ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, _params.relay_on);
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)
|
|
|
|
trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2023-03-06 19:04:43 -04:00
|
|
|
#endif // AP_CAMERA_RELAY_ENABLED
|