CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Camera/AP_Camera_Servo.cpp
Views: 1798
1
#include "AP_Camera_Servo.h"
2
3
#if AP_CAMERA_SERVO_ENABLED
4
5
#include <SRV_Channel/SRV_Channel.h>
6
7
extern const AP_HAL::HAL& hal;
8
9
// update - should be called at 50hz
10
void AP_Camera_Servo::update()
11
{
12
// shutter counter
13
if (trigger_counter > 0) {
14
trigger_counter--;
15
} else {
16
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_off_pwm);
17
}
18
19
// iso counter
20
if (iso_counter > 0) {
21
iso_counter--;
22
} else {
23
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_off_pwm);
24
}
25
26
// call parent update
27
AP_Camera_Backend::update();
28
}
29
30
// entry point to actually take a picture. returns true on success
31
bool AP_Camera_Servo::trigger_pic()
32
{
33
// fail if have not completed previous picture
34
if (trigger_counter > 0) {
35
return false;
36
}
37
38
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_on_pwm);
39
40
// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)
41
trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
42
43
return true;
44
}
45
46
// configure camera
47
void AP_Camera_Servo::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)
48
{
49
// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras
50
// if the message contains non zero values then use them for the below functions
51
if (ISO > 0) {
52
// set a trigger for the iso function that is flip controlled
53
iso_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
54
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_on_pwm);
55
}
56
57
if (aperture > 0) {
58
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_aperture, (uint16_t)aperture);
59
}
60
61
if (shutter_speed > 0) {
62
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_shutter_speed, (uint16_t)shutter_speed);
63
}
64
65
// Use the shooting mode PWM value for the BMMCC as the focus control - no need to modify or create a new MAVlink message type.
66
if (shooting_mode > 0) {
67
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_focus, (uint16_t)shooting_mode);
68
}
69
}
70
71
#endif // AP_CAMERA_SERVO_ENABLED
72
73