Path: blob/master/libraries/AP_Camera/AP_Camera_Servo.cpp
9441 views
#include "AP_Camera_Servo.h"12#if AP_CAMERA_SERVO_ENABLED34#include <SRV_Channel/SRV_Channel.h>56extern const AP_HAL::HAL& hal;78// initialize the AP_Camera_Servo driver9void AP_Camera_Servo::init()10{11// set the zoom and focus to the trim point12SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, 500);13SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, 500);14}1516// update - should be called at 50hz17void AP_Camera_Servo::update()18{19// shutter counter20if (trigger_counter > 0) {21trigger_counter--;22} else {23SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_off_pwm);24}2526// iso counter27if (iso_counter > 0) {28iso_counter--;29} else {30SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_off_pwm);31}32float current_zoom = SRV_Channels::get_output_scaled(SRV_Channel::k_cam_zoom);33float new_zoom = constrain_float(current_zoom + zoom_current_rate, 0, 1000);34SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, new_zoom);3536float current_focus = SRV_Channels::get_output_scaled(SRV_Channel::k_cam_focus);37float new_focus = constrain_float(current_focus + focus_current_rate, 0, 1000);38SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, new_focus);3940// call parent update41AP_Camera_Backend::update();42}4344// entry point to actually take a picture. returns true on success45bool AP_Camera_Servo::trigger_pic()46{47// fail if have not completed previous picture48if (trigger_counter > 0) {49return false;50}5152SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_on_pwm);5354// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)55trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);5657return true;58}596061bool AP_Camera_Servo::set_zoom(ZoomType zoom_type, float zoom_value)62{63switch (zoom_type) {64case ZoomType::RATE:65zoom_current_rate = zoom_value;66return true;67case ZoomType::PCT:68// expects to receive a value between 0 and 10069// This maps it to our 0-1000 range70SRV_Channels::set_output_scaled(SRV_Channel::k_cam_zoom, constrain_float(zoom_value * 10, 0, 1000));71return true;72}73return false;74}7576// set focus specified as rate77SetFocusResult AP_Camera_Servo::set_focus(FocusType focus_type, float focus_value)78{79switch (focus_type) {80case FocusType::RATE:81focus_current_rate = focus_value;82return SetFocusResult::ACCEPTED;83case FocusType::PCT:84// expects to receive a value between 0 and 10085// This maps it to our 0-1000 range86SRV_Channels::set_output_scaled(SRV_Channel::k_cam_focus, constrain_float(focus_value * 10, 0, 1000));87return SetFocusResult::ACCEPTED;88case FocusType::AUTO:89return SetFocusResult::UNSUPPORTED;90}91return SetFocusResult::UNSUPPORTED;92}9394// configure camera95void 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)96{97// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras98// if the message contains non zero values then use them for the below functions99if (ISO > 0) {100// set a trigger for the iso function that is flip controlled101iso_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);102SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_on_pwm);103}104105if (aperture > 0) {106SRV_Channels::set_output_pwm(SRV_Channel::k_cam_aperture, (uint16_t)aperture);107}108109if (shutter_speed > 0) {110SRV_Channels::set_output_pwm(SRV_Channel::k_cam_shutter_speed, (uint16_t)shutter_speed);111}112113// Use the shooting mode PWM value for the BMMCC as the focus control - no need to modify or create a new MAVlink message type.114if (shooting_mode > 0) {115SRV_Channels::set_output_pwm(SRV_Channel::k_cam_focus, (uint16_t)shooting_mode);116}117}118119// send camera settings message to GCS120void AP_Camera_Servo::send_camera_settings(mavlink_channel_t chan) const121{122mavlink_msg_camera_settings_send(123chan,124AP_HAL::millis(), // time_boot_ms125CAMERA_MODE_IMAGE, // camera mode (0:image, 1:video, 2:image survey)126SRV_Channels::get_output_scaled(SRV_Channel::k_cam_zoom) / 10.0f, // zoomLevel float, percentage from 0 to 100, 0 if unassigned127SRV_Channels::get_output_scaled(SRV_Channel::k_cam_focus) / 10.0f); // focusLevel float, percentage from 0 to 100, 0 if unassigned128}129130#endif // AP_CAMERA_SERVO_ENABLED131132133