Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Camera/AP_Camera_Servo.cpp
9441 views
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
// initialize the AP_Camera_Servo driver
10
void AP_Camera_Servo::init()
11
{
12
// set the zoom and focus to the trim point
13
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, 500);
14
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, 500);
15
}
16
17
// update - should be called at 50hz
18
void AP_Camera_Servo::update()
19
{
20
// shutter counter
21
if (trigger_counter > 0) {
22
trigger_counter--;
23
} else {
24
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_off_pwm);
25
}
26
27
// iso counter
28
if (iso_counter > 0) {
29
iso_counter--;
30
} else {
31
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_off_pwm);
32
}
33
float current_zoom = SRV_Channels::get_output_scaled(SRV_Channel::k_cam_zoom);
34
float new_zoom = constrain_float(current_zoom + zoom_current_rate, 0, 1000);
35
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, new_zoom);
36
37
float current_focus = SRV_Channels::get_output_scaled(SRV_Channel::k_cam_focus);
38
float new_focus = constrain_float(current_focus + focus_current_rate, 0, 1000);
39
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, new_focus);
40
41
// call parent update
42
AP_Camera_Backend::update();
43
}
44
45
// entry point to actually take a picture. returns true on success
46
bool AP_Camera_Servo::trigger_pic()
47
{
48
// fail if have not completed previous picture
49
if (trigger_counter > 0) {
50
return false;
51
}
52
53
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_on_pwm);
54
55
// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)
56
trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
57
58
return true;
59
}
60
61
62
bool AP_Camera_Servo::set_zoom(ZoomType zoom_type, float zoom_value)
63
{
64
switch (zoom_type) {
65
case ZoomType::RATE:
66
zoom_current_rate = zoom_value;
67
return true;
68
case ZoomType::PCT:
69
// expects to receive a value between 0 and 100
70
// This maps it to our 0-1000 range
71
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, constrain_float(zoom_value * 10, 0, 1000));
72
return true;
73
}
74
return false;
75
}
76
77
// set focus specified as rate
78
SetFocusResult AP_Camera_Servo::set_focus(FocusType focus_type, float focus_value)
79
{
80
switch (focus_type) {
81
case FocusType::RATE:
82
focus_current_rate = focus_value;
83
return SetFocusResult::ACCEPTED;
84
case FocusType::PCT:
85
// expects to receive a value between 0 and 100
86
// This maps it to our 0-1000 range
87
SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, constrain_float(focus_value * 10, 0, 1000));
88
return SetFocusResult::ACCEPTED;
89
case FocusType::AUTO:
90
return SetFocusResult::UNSUPPORTED;
91
}
92
return SetFocusResult::UNSUPPORTED;
93
}
94
95
// configure camera
96
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)
97
{
98
// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras
99
// if the message contains non zero values then use them for the below functions
100
if (ISO > 0) {
101
// set a trigger for the iso function that is flip controlled
102
iso_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);
103
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_on_pwm);
104
}
105
106
if (aperture > 0) {
107
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_aperture, (uint16_t)aperture);
108
}
109
110
if (shutter_speed > 0) {
111
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_shutter_speed, (uint16_t)shutter_speed);
112
}
113
114
// Use the shooting mode PWM value for the BMMCC as the focus control - no need to modify or create a new MAVlink message type.
115
if (shooting_mode > 0) {
116
SRV_Channels::set_output_pwm(SRV_Channel::k_cam_focus, (uint16_t)shooting_mode);
117
}
118
}
119
120
// send camera settings message to GCS
121
void AP_Camera_Servo::send_camera_settings(mavlink_channel_t chan) const
122
{
123
mavlink_msg_camera_settings_send(
124
chan,
125
AP_HAL::millis(), // time_boot_ms
126
CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey)
127
SRV_Channels::get_output_scaled(SRV_Channel::k_cam_zoom) / 10.0f, // zoomLevel float, percentage from 0 to 100, 0 if unassigned
128
SRV_Channels::get_output_scaled(SRV_Channel::k_cam_focus) / 10.0f); // focusLevel float, percentage from 0 to 100, 0 if unassigned
129
}
130
131
#endif // AP_CAMERA_SERVO_ENABLED
132
133