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_MAVLink.cpp
Views: 1798
#include "AP_Camera_MAVLink.h"12#if AP_CAMERA_MAVLINK_ENABLED3#include <GCS_MAVLink/GCS.h>45extern const AP_HAL::HAL& hal;67// entry point to actually take a picture. returns true on success8bool AP_Camera_MAVLink::trigger_pic()9{10// tell all of our components to take a picture:11mavlink_command_long_t cmd_msg {};12cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;13cmd_msg.param5 = 1;1415// forward to all components16GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&cmd_msg, sizeof(cmd_msg));17return true;18}1920// configure camera21void AP_Camera_MAVLink::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, int32_t exposure_type, int32_t cmd_id, float engine_cutoff_time)22{23// convert to mavlink message and send to all components24mavlink_command_long_t mav_cmd_long = {};2526// convert mission command to mavlink command_long27mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONFIGURE;28mav_cmd_long.param1 = shooting_mode;29mav_cmd_long.param2 = shutter_speed;30mav_cmd_long.param3 = aperture;31mav_cmd_long.param4 = ISO;32mav_cmd_long.param5 = float(exposure_type);33mav_cmd_long.param6 = float(cmd_id);34mav_cmd_long.param7 = engine_cutoff_time;3536// send to all components37GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&mav_cmd_long, sizeof(mav_cmd_long));38}3940// handle camera control message41void AP_Camera_MAVLink::control(float session, float zoom_pos, float zoom_step, float focus_lock, int32_t shooting_cmd, int32_t cmd_id)42{43// take picture and ignore other arguments44if (shooting_cmd == 1) {45take_picture();46return;47}4849// convert command to mavlink command long50mavlink_command_long_t mav_cmd_long = {};51mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONTROL;52mav_cmd_long.param1 = session;53mav_cmd_long.param2 = zoom_pos;54mav_cmd_long.param3 = zoom_step;55mav_cmd_long.param4 = focus_lock;56mav_cmd_long.param5 = float(shooting_cmd);57mav_cmd_long.param6 = float(cmd_id);5859// send to all components60GCS_MAVLINK::send_to_components(MAVLINK_MSG_ID_COMMAND_LONG, (char*)&mav_cmd_long, sizeof(mav_cmd_long));61}6263#endif // AP_CAMERA_MAVLINK_ENABLED646566