Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Camera/AP_Camera_Servo.cpp
Views: 1798
#include "AP_Camera_Servo.h"12#if AP_CAMERA_SERVO_ENABLED34#include <SRV_Channel/SRV_Channel.h>56extern const AP_HAL::HAL& hal;78// update - should be called at 50hz9void AP_Camera_Servo::update()10{11// shutter counter12if (trigger_counter > 0) {13trigger_counter--;14} else {15SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_off_pwm);16}1718// iso counter19if (iso_counter > 0) {20iso_counter--;21} else {22SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_off_pwm);23}2425// call parent update26AP_Camera_Backend::update();27}2829// entry point to actually take a picture. returns true on success30bool AP_Camera_Servo::trigger_pic()31{32// fail if have not completed previous picture33if (trigger_counter > 0) {34return false;35}3637SRV_Channels::set_output_pwm(SRV_Channel::k_cam_trigger, _params.servo_on_pwm);3839// set counter to move servo to off position after this many iterations of update (assumes 50hz update rate)40trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);4142return true;43}4445// configure camera46void 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)47{48// designed to control Blackmagic Micro Cinema Camera (BMMCC) cameras49// if the message contains non zero values then use them for the below functions50if (ISO > 0) {51// set a trigger for the iso function that is flip controlled52iso_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX);53SRV_Channels::set_output_pwm(SRV_Channel::k_cam_iso, _params.servo_on_pwm);54}5556if (aperture > 0) {57SRV_Channels::set_output_pwm(SRV_Channel::k_cam_aperture, (uint16_t)aperture);58}5960if (shutter_speed > 0) {61SRV_Channels::set_output_pwm(SRV_Channel::k_cam_shutter_speed, (uint16_t)shutter_speed);62}6364// Use the shooting mode PWM value for the BMMCC as the focus control - no need to modify or create a new MAVlink message type.65if (shooting_mode > 0) {66SRV_Channels::set_output_pwm(SRV_Channel::k_cam_focus, (uint16_t)shooting_mode);67}68}6970#endif // AP_CAMERA_SERVO_ENABLED717273