// do_take_picture - take a picture with the camera library void Plane::do_take_picture() { #if CAMERA == ENABLED camera.trigger_pic(true); log_picture(); #endif }
// do_digicam_control Send Digicam Control message with the camera library void Plane::do_digicam_control(const AP_Mission::Mission_Command& cmd) { #if CAMERA == ENABLED camera.control_cmd(cmd); log_picture(); #endif }
// do_digicam_control Send Digicam Control message with the camera library void Rover::do_digicam_control(const AP_Mission::Mission_Command& cmd) { if (camera.control(cmd.content.digicam_control.session, cmd.content.digicam_control.zoom_pos, cmd.content.digicam_control.zoom_step, cmd.content.digicam_control.focus_lock, cmd.content.digicam_control.shooting_cmd, cmd.content.digicam_control.cmd_id)) { log_picture(); } }
// do_digicam_control Send Digicam Control message with the camera library void Copter::do_digicam_control(const AP_Mission::Mission_Command& cmd) { #if CAMERA == ENABLED camera.control(cmd.content.digicam_control.session, cmd.content.digicam_control.zoom_pos, cmd.content.digicam_control.zoom_step, cmd.content.digicam_control.focus_lock, cmd.content.digicam_control.shooting_cmd, cmd.content.digicam_control.cmd_id); log_picture(); #endif }
/// single entry point to take pictures /// set send_mavlink_msg to true to send DO_DIGICAM_CONTROL message to all components void AP_Camera::trigger_pic() { setup_feedback_callback(); _image_index++; switch (_trigger_type) { case AP_CAMERA_TRIGGER_TYPE_SERVO: servo_pic(); // Servo operated camera break; case AP_CAMERA_TRIGGER_TYPE_RELAY: relay_pic(); // basic relay activation break; } log_picture(); }
// do_take_picture - take a picture with the camera library void Rover::do_take_picture() { camera.trigger_pic(true); log_picture(); }