2015-08-11 03:28:42 -03:00
|
|
|
#include "AP_Camera.h"
|
2019-06-27 04:23:37 -03:00
|
|
|
|
2022-06-02 05:28:26 -03:00
|
|
|
#if AP_CAMERA_ENABLED
|
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2019-04-04 07:46:40 -03:00
|
|
|
#include <SRV_Channel/SRV_Channel.h>
|
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2023-02-10 20:27:39 -04:00
|
|
|
#include "AP_Camera_Backend.h"
|
|
|
|
#include "AP_Camera_Servo.h"
|
|
|
|
#include "AP_Camera_Relay.h"
|
2023-03-03 02:50:07 -04:00
|
|
|
#include "AP_Camera_SoloGimbal.h"
|
2023-02-10 20:27:39 -04:00
|
|
|
#include "AP_Camera_Mount.h"
|
|
|
|
#include "AP_Camera_MAVLink.h"
|
2023-03-03 02:50:07 -04:00
|
|
|
#include "AP_Camera_MAVLinkCamV2.h"
|
2023-04-07 23:35:51 -03:00
|
|
|
#include "AP_Camera_Scripting.h"
|
2012-06-13 16:00:20 -03:00
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo AP_Camera::var_info[] = {
|
2015-12-18 03:16:11 -04:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// @Param: _MAX_ROLL
|
2015-12-18 03:16:11 -04:00
|
|
|
// @DisplayName: Maximum photo roll angle.
|
|
|
|
// @Description: Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
|
|
|
|
// @User: Standard
|
2017-05-02 10:42:29 -03:00
|
|
|
// @Units: deg
|
2015-12-18 03:16:11 -04:00
|
|
|
// @Range: 0 180
|
2023-02-10 20:27:39 -04:00
|
|
|
AP_GROUPINFO("_MAX_ROLL", 7, AP_Camera, _max_roll, 0),
|
2015-12-18 03:16:11 -04:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// @Param: _AUTO_ONLY
|
2017-10-24 07:42:17 -03:00
|
|
|
// @DisplayName: Distance-trigging in AUTO mode only
|
|
|
|
// @Description: When enabled, trigging by distance is done in AUTO mode only.
|
|
|
|
// @Values: 0:Always,1:Only when in AUTO
|
|
|
|
// @User: Standard
|
2023-02-10 20:27:39 -04:00
|
|
|
AP_GROUPINFO("_AUTO_ONLY", 10, AP_Camera, _auto_mode_only, 0),
|
2017-10-24 07:42:17 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// @Group: 1
|
|
|
|
// @Path: AP_Camera_Params.cpp
|
|
|
|
AP_SUBGROUPINFO(_params[0], "1", 12, AP_Camera, AP_Camera_Params),
|
|
|
|
|
|
|
|
#if AP_CAMERA_MAX_INSTANCES > 1
|
|
|
|
// @Group: 2
|
|
|
|
// @Path: AP_Camera_Params.cpp
|
|
|
|
AP_SUBGROUPINFO(_params[1], "2", 13, AP_Camera, AP_Camera_Params),
|
|
|
|
#endif
|
2018-10-03 21:26:34 -03:00
|
|
|
|
2012-08-17 03:09:29 -03:00
|
|
|
AP_GROUPEND
|
2012-06-13 16:00:20 -03:00
|
|
|
};
|
|
|
|
|
2015-12-18 03:16:11 -04:00
|
|
|
extern const AP_HAL::HAL& hal;
|
2012-06-13 16:00:20 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
AP_Camera::AP_Camera(uint32_t _log_camera_bit) :
|
|
|
|
log_camera_bit(_log_camera_bit)
|
2012-06-13 16:00:20 -03:00
|
|
|
{
|
2023-02-10 20:27:39 -04:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
_singleton = this;
|
2012-06-13 16:00:20 -03:00
|
|
|
}
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// set camera trigger distance in a mission
|
|
|
|
void AP_Camera::set_trigger_distance(float distance_m)
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
primary->set_trigger_distance(distance_m);
|
|
|
|
}
|
|
|
|
|
|
|
|
// momentary switch to change camera between picture and video modes
|
|
|
|
void AP_Camera::cam_mode_toggle()
|
2012-06-13 16:00:20 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
2015-09-05 00:44:07 -03:00
|
|
|
}
|
2023-03-06 17:41:41 -04:00
|
|
|
primary->cam_mode_toggle();
|
|
|
|
}
|
2012-12-06 04:46:09 -04:00
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// take a picture
|
|
|
|
void AP_Camera::take_picture()
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
primary->take_picture();
|
|
|
|
}
|
|
|
|
|
2023-08-04 03:08:32 -03:00
|
|
|
// take multiple pictures, time_interval between two consecutive pictures is in miliseconds
|
|
|
|
// total_num is number of pictures to be taken, -1 means capture forever
|
|
|
|
void AP_Camera::take_multiple_pictures(uint32_t time_interval_ms, int16_t total_num)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
primary->take_multiple_pictures(time_interval_ms, total_num);
|
|
|
|
}
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// start/stop recording video
|
|
|
|
// start_recording should be true to start recording, false to stop recording
|
|
|
|
bool AP_Camera::record_video(bool start_recording)
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return primary->record_video(start_recording);
|
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// detect and initialise backends
|
|
|
|
void AP_Camera::init()
|
2012-06-13 16:00:20 -03:00
|
|
|
{
|
2023-02-10 20:27:39 -04:00
|
|
|
// check init has not been called before
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary != nullptr) {
|
2023-02-10 20:27:39 -04:00
|
|
|
return;
|
2012-08-17 03:09:29 -03:00
|
|
|
}
|
2015-03-28 22:36:43 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// perform any required parameter conversion
|
|
|
|
convert_params();
|
2012-06-13 16:00:20 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// create each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
2023-03-06 17:41:41 -04:00
|
|
|
switch ((CameraType)_params[instance].type.get()) {
|
2023-03-06 19:04:45 -04:00
|
|
|
#if AP_CAMERA_SERVO_ENABLED
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::SERVO:
|
2023-02-10 20:27:39 -04:00
|
|
|
_backends[instance] = new AP_Camera_Servo(*this, _params[instance], instance);
|
2023-03-06 17:41:41 -04:00
|
|
|
break;
|
2023-03-06 19:04:45 -04:00
|
|
|
#endif
|
2023-03-06 19:04:43 -04:00
|
|
|
#if AP_CAMERA_RELAY_ENABLED
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::RELAY:
|
2023-02-10 20:27:39 -04:00
|
|
|
_backends[instance] = new AP_Camera_Relay(*this, _params[instance], instance);
|
2023-03-06 17:41:41 -04:00
|
|
|
break;
|
2023-03-06 19:04:43 -04:00
|
|
|
#endif
|
2023-03-06 19:04:39 -04:00
|
|
|
#if AP_CAMERA_SOLOGIMBAL_ENABLED
|
2023-02-10 20:27:39 -04:00
|
|
|
// check for GoPro in Solo camera
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::SOLOGIMBAL:
|
2023-02-10 20:27:39 -04:00
|
|
|
_backends[instance] = new AP_Camera_SoloGimbal(*this, _params[instance], instance);
|
2023-03-06 17:41:41 -04:00
|
|
|
break;
|
2020-07-24 14:31:42 -03:00
|
|
|
#endif
|
2023-03-06 18:15:58 -04:00
|
|
|
#if AP_CAMERA_MOUNT_ENABLED
|
2023-02-10 20:27:39 -04:00
|
|
|
// check for Mount camera
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::MOUNT:
|
2023-02-10 20:27:39 -04:00
|
|
|
_backends[instance] = new AP_Camera_Mount(*this, _params[instance], instance);
|
2023-03-06 17:41:41 -04:00
|
|
|
break;
|
2023-03-06 18:15:58 -04:00
|
|
|
#endif
|
2023-03-06 19:04:30 -04:00
|
|
|
#if AP_CAMERA_MAVLINK_ENABLED
|
2023-02-10 20:27:39 -04:00
|
|
|
// check for MAVLink enabled camera driver
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::MAVLINK:
|
2023-02-10 20:27:39 -04:00
|
|
|
_backends[instance] = new AP_Camera_MAVLink(*this, _params[instance], instance);
|
2023-03-06 17:41:41 -04:00
|
|
|
break;
|
2023-04-04 03:36:54 -03:00
|
|
|
#endif
|
|
|
|
#if AP_CAMERA_MAVLINKCAMV2_ENABLED
|
2023-03-03 02:50:07 -04:00
|
|
|
// check for MAVLink Camv2 driver
|
|
|
|
case CameraType::MAVLINK_CAMV2:
|
|
|
|
_backends[instance] = new AP_Camera_MAVLinkCamV2(*this, _params[instance], instance);
|
|
|
|
break;
|
2023-04-07 23:35:51 -03:00
|
|
|
#endif
|
|
|
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
|
|
|
// check for Scripting driver
|
|
|
|
case CameraType::SCRIPTING:
|
|
|
|
_backends[instance] = new AP_Camera_Scripting(*this, _params[instance], instance);
|
|
|
|
break;
|
2023-03-06 19:04:30 -04:00
|
|
|
#endif
|
2023-03-06 17:41:41 -04:00
|
|
|
case CameraType::NONE:
|
|
|
|
break;
|
2018-10-03 21:26:34 -03:00
|
|
|
}
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// set primary to first non-null instance
|
|
|
|
if (primary == nullptr) {
|
|
|
|
primary = _backends[instance];
|
2018-10-03 21:26:34 -03:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
2018-10-03 21:26:34 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// init each instance, do it after all instances were created, so that they all know things
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->init();
|
2018-10-03 21:26:34 -03:00
|
|
|
}
|
|
|
|
}
|
2015-04-18 10:30:03 -03:00
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// handle incoming mavlink messages
|
|
|
|
void AP_Camera::handle_message(mavlink_channel_t chan, const mavlink_message_t &msg)
|
2015-04-18 10:30:03 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_DIGICAM_CONTROL) {
|
|
|
|
// decode deprecated MavLink message that controls camera.
|
|
|
|
__mavlink_digicam_control_t packet;
|
|
|
|
mavlink_msg_digicam_control_decode(&msg, &packet);
|
|
|
|
control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);
|
|
|
|
return;
|
2015-09-06 17:41:47 -03:00
|
|
|
}
|
2015-04-18 10:43:23 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->handle_message(chan, msg);
|
|
|
|
}
|
2014-10-31 02:40:27 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-03-07 02:39:52 -04:00
|
|
|
// handle command_long mavlink messages
|
|
|
|
MAV_RESULT AP_Camera::handle_command_long(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
switch (packet.command) {
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONFIGURE:
|
|
|
|
configure(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6, packet.param7);
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
case MAV_CMD_DO_DIGICAM_CONTROL:
|
|
|
|
control(packet.param1, packet.param2, packet.param3, packet.param4, packet.param5, packet.param6);
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
|
|
|
|
set_trigger_distance(packet.param1);
|
|
|
|
if (is_equal(packet.param3, 1.0f)) {
|
|
|
|
take_picture();
|
|
|
|
}
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
2023-03-07 03:10:56 -04:00
|
|
|
case MAV_CMD_SET_CAMERA_ZOOM:
|
2023-04-06 21:49:46 -03:00
|
|
|
if (is_equal(packet.param1, (float)ZOOM_TYPE_CONTINUOUS) &&
|
2023-04-18 22:06:16 -03:00
|
|
|
set_zoom(ZoomType::RATE, packet.param2)) {
|
2023-04-06 21:49:46 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
if (is_equal(packet.param1, (float)ZOOM_TYPE_RANGE) &&
|
2023-04-18 22:06:16 -03:00
|
|
|
set_zoom(ZoomType::PCT, packet.param2)) {
|
2023-03-07 03:10:56 -04:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
case MAV_CMD_SET_CAMERA_FOCUS:
|
|
|
|
// accept any of the auto focus types
|
2023-06-21 03:03:39 -03:00
|
|
|
switch ((SET_FOCUS_TYPE)packet.param1) {
|
|
|
|
case FOCUS_TYPE_AUTO:
|
|
|
|
case FOCUS_TYPE_AUTO_SINGLE:
|
|
|
|
case FOCUS_TYPE_AUTO_CONTINUOUS:
|
|
|
|
return (MAV_RESULT)set_focus(FocusType::AUTO, 0);
|
|
|
|
case FOCUS_TYPE_CONTINUOUS:
|
2023-04-24 09:23:07 -03:00
|
|
|
// accept continuous manual focus
|
2023-06-21 03:03:39 -03:00
|
|
|
return (MAV_RESULT)set_focus(FocusType::RATE, packet.param2);
|
2023-04-24 09:23:07 -03:00
|
|
|
// accept focus as percentage
|
2023-06-21 03:03:39 -03:00
|
|
|
case FOCUS_TYPE_RANGE:
|
|
|
|
return (MAV_RESULT)set_focus(FocusType::PCT, packet.param2);
|
|
|
|
case SET_FOCUS_TYPE_ENUM_END:
|
|
|
|
case FOCUS_TYPE_STEP:
|
|
|
|
case FOCUS_TYPE_METERS:
|
|
|
|
// unsupported focus (bad parameter)
|
|
|
|
break;
|
2023-03-07 03:10:56 -04:00
|
|
|
}
|
2023-06-21 03:03:39 -03:00
|
|
|
return MAV_RESULT_DENIED;
|
2023-03-07 03:10:56 -04:00
|
|
|
case MAV_CMD_IMAGE_START_CAPTURE:
|
|
|
|
if (!is_zero(packet.param2) || !is_equal(packet.param3, 1.0f) || !is_zero(packet.param4)) {
|
2023-08-04 03:08:32 -03:00
|
|
|
// Its a multiple picture request
|
|
|
|
if (is_equal(packet.param3, 0.0f)) {
|
|
|
|
take_multiple_pictures(packet.param2*1000, -1);
|
|
|
|
} else {
|
|
|
|
take_multiple_pictures(packet.param2*1000, packet.param3);
|
|
|
|
}
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
2023-03-07 03:10:56 -04:00
|
|
|
}
|
|
|
|
take_picture();
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
2023-04-28 21:39:05 -03:00
|
|
|
case MAV_CMD_CAMERA_TRACK_POINT:
|
2023-05-10 02:09:33 -03:00
|
|
|
if (set_tracking(TrackingType::TRK_POINT, Vector2f{packet.param1, packet.param2}, Vector2f{})) {
|
2023-04-28 21:39:05 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
case MAV_CMD_CAMERA_TRACK_RECTANGLE:
|
2023-05-10 02:09:33 -03:00
|
|
|
if (set_tracking(TrackingType::TRK_RECTANGLE, Vector2f{packet.param1, packet.param2}, Vector2f{packet.param3, packet.param4})) {
|
2023-04-28 21:39:05 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
case MAV_CMD_CAMERA_STOP_TRACKING:
|
2023-05-10 02:09:33 -03:00
|
|
|
if (set_tracking(TrackingType::TRK_NONE, Vector2f{}, Vector2f{})) {
|
2023-04-28 21:39:05 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
2023-03-07 03:10:56 -04:00
|
|
|
case MAV_CMD_VIDEO_START_CAPTURE:
|
|
|
|
case MAV_CMD_VIDEO_STOP_CAPTURE:
|
|
|
|
{
|
|
|
|
bool success = false;
|
|
|
|
const bool start_recording = (packet.command == MAV_CMD_VIDEO_START_CAPTURE);
|
|
|
|
const uint8_t stream_id = packet.param1; // Stream ID
|
|
|
|
if (stream_id == 0) {
|
|
|
|
// stream id of 0 interpreted as primary camera
|
|
|
|
success = record_video(start_recording);
|
|
|
|
} else {
|
|
|
|
// convert stream id to instance id
|
|
|
|
success = record_video(stream_id - 1, start_recording);
|
|
|
|
}
|
|
|
|
if (success) {
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
}
|
2023-03-07 02:39:52 -04:00
|
|
|
default:
|
|
|
|
return MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// set camera trigger distance in a mission
|
|
|
|
void AP_Camera::set_trigger_distance(uint8_t instance, float distance_m)
|
2013-06-24 09:39:50 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2017-07-25 23:45:20 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
backend->set_trigger_distance(distance_m);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
2019-03-26 08:06:18 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// momentary switch to change camera between picture and video modes
|
|
|
|
void AP_Camera::cam_mode_toggle(uint8_t instance)
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2017-07-25 23:45:20 -03:00
|
|
|
return;
|
2013-06-24 09:39:50 -03:00
|
|
|
}
|
2015-12-18 03:16:11 -04:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
backend->cam_mode_toggle();
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
2015-12-18 03:16:11 -04:00
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// configure camera
|
2023-02-10 20:27:39 -04:00
|
|
|
void AP_Camera::configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
primary->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);
|
2023-02-10 20:27:39 -04:00
|
|
|
}
|
2015-12-18 03:16:11 -04:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
void AP_Camera::configure(uint8_t instance, float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
|
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2018-10-03 21:26:34 -03:00
|
|
|
return;
|
2017-10-24 07:42:17 -03:00
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
backend->configure(shooting_mode, shutter_speed, aperture, ISO, exposure_type, cmd_id, engine_cutoff_time);
|
2016-01-19 01:25:53 -04:00
|
|
|
}
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// handle camera control
|
2023-02-10 20:27:39 -04:00
|
|
|
void AP_Camera::control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
|
2018-05-14 22:03:49 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
if (primary == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
primary->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);
|
2018-05-14 22:03:49 -03:00
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
void AP_Camera::control(uint8_t instance, float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
|
2016-01-19 01:25:53 -04:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2023-02-10 20:27:39 -04:00
|
|
|
return;
|
2016-01-19 01:25:53 -04:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
backend->control(session, zoom_pos, zoom_step, focus_lock, shooting_cmd, cmd_id);
|
2016-01-19 01:25:53 -04:00
|
|
|
}
|
|
|
|
|
2016-04-14 20:24:41 -03:00
|
|
|
/*
|
2023-02-10 20:27:39 -04:00
|
|
|
Send camera feedback to the GCS
|
2016-04-14 20:24:41 -03:00
|
|
|
*/
|
2023-04-11 21:11:26 -03:00
|
|
|
void AP_Camera::send_feedback(mavlink_channel_t chan)
|
2016-04-14 20:24:41 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->send_camera_feedback(chan);
|
|
|
|
}
|
2018-05-14 22:03:49 -03:00
|
|
|
}
|
2016-04-14 20:24:41 -03:00
|
|
|
}
|
2017-07-25 23:45:20 -03:00
|
|
|
|
2023-06-09 23:17:12 -03:00
|
|
|
// send camera information message to GCS
|
|
|
|
void AP_Camera::send_camera_information(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
// call each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->send_camera_information(chan);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// send camera settings message to GCS
|
|
|
|
void AP_Camera::send_camera_settings(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
// call each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->send_camera_settings(chan);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
/*
|
|
|
|
update; triggers by distance moved and camera trigger
|
|
|
|
*/
|
|
|
|
void AP_Camera::update()
|
2017-07-25 23:45:20 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call each instance
|
|
|
|
for (uint8_t instance = 0; instance < AP_CAMERA_MAX_INSTANCES; instance++) {
|
|
|
|
if (_backends[instance] != nullptr) {
|
|
|
|
_backends[instance]->update();
|
|
|
|
}
|
2017-07-25 23:45:20 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// take_picture - take a picture
|
2023-02-10 20:27:39 -04:00
|
|
|
void AP_Camera::take_picture(uint8_t instance)
|
2017-07-25 23:45:20 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2022-11-07 06:03:43 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
backend->take_picture();
|
2017-07-25 23:45:20 -03:00
|
|
|
}
|
|
|
|
|
2022-09-26 09:06:45 -03:00
|
|
|
// start/stop recording video. returns true on success
|
|
|
|
// start_recording should be true to start recording, false to stop recording
|
2023-02-10 20:27:39 -04:00
|
|
|
bool AP_Camera::record_video(uint8_t instance, bool start_recording)
|
2022-09-26 09:06:45 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2023-02-10 20:27:39 -04:00
|
|
|
return false;
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
// call backend
|
2023-03-06 17:41:41 -04:00
|
|
|
return backend->record_video(start_recording);
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
|
|
|
|
2023-04-06 21:49:46 -03:00
|
|
|
// zoom specified as a rate or percentage
|
|
|
|
bool AP_Camera::set_zoom(ZoomType zoom_type, float zoom_value)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
if (primary == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return primary->set_zoom(zoom_type, zoom_value);
|
|
|
|
}
|
|
|
|
|
|
|
|
// zoom specified as a rate or percentage
|
|
|
|
bool AP_Camera::set_zoom(uint8_t instance, ZoomType zoom_type, float zoom_value)
|
2022-09-26 09:06:45 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2023-02-10 20:27:39 -04:00
|
|
|
return false;
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
// call each instance
|
2023-04-06 21:49:46 -03:00
|
|
|
return backend->set_zoom(zoom_type, zoom_value);
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
|
|
|
|
// set focus specified as rate, percentage or auto
|
2022-09-26 09:06:45 -03:00
|
|
|
// focus in = -1, focus hold = 0, focus out = 1
|
2023-06-21 03:03:39 -03:00
|
|
|
SetFocusResult AP_Camera::set_focus(FocusType focus_type, float focus_value)
|
2022-09-26 09:06:45 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
if (primary == nullptr) {
|
2023-06-21 03:03:39 -03:00
|
|
|
return SetFocusResult::FAILED;
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
2023-04-24 09:23:07 -03:00
|
|
|
return primary->set_focus(focus_type, focus_value);
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
// set focus specified as rate, percentage or auto
|
|
|
|
// focus in = -1, focus hold = 0, focus out = 1
|
2023-06-21 03:03:39 -03:00
|
|
|
SetFocusResult AP_Camera::set_focus(uint8_t instance, FocusType focus_type, float focus_value)
|
2022-09-26 09:06:45 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
2023-06-21 03:03:39 -03:00
|
|
|
return SetFocusResult::FAILED;
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
|
2023-04-24 09:23:07 -03:00
|
|
|
// call each instance
|
|
|
|
return backend->set_focus(focus_type, focus_value);
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
|
|
|
|
2023-04-28 21:39:05 -03:00
|
|
|
// set tracking to none, point or rectangle (see TrackingType enum)
|
|
|
|
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
|
|
|
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
|
|
|
bool AP_Camera::set_tracking(TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
if (primary == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return primary->set_tracking(tracking_type, p1, p2);
|
|
|
|
}
|
|
|
|
|
|
|
|
// set tracking to none, point or rectangle (see TrackingType enum)
|
|
|
|
// if POINT only p1 is used, if RECTANGLE then p1 is top-left, p2 is bottom-right
|
|
|
|
// p1,p2 are in range 0 to 1. 0 is left or top, 1 is right or bottom
|
|
|
|
bool AP_Camera::set_tracking(uint8_t instance, TrackingType tracking_type, const Vector2f& p1, const Vector2f& p2)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// call each instance
|
|
|
|
return backend->set_tracking(tracking_type, p1, p2);
|
|
|
|
}
|
|
|
|
|
2023-07-14 08:21:02 -03:00
|
|
|
// set camera lens as a value from 0 to 5
|
|
|
|
bool AP_Camera::set_lens(uint8_t lens)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
if (primary == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return primary->set_lens(lens);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_Camera::set_lens(uint8_t instance, uint8_t lens)
|
|
|
|
{
|
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// call instance
|
|
|
|
return backend->set_lens(lens);
|
|
|
|
}
|
|
|
|
|
2023-04-07 23:35:51 -03:00
|
|
|
#if AP_CAMERA_SCRIPTING_ENABLED
|
|
|
|
// accessor to allow scripting backend to retrieve state
|
|
|
|
// returns true on success and cam_state is filled in
|
2023-04-11 21:11:26 -03:00
|
|
|
bool AP_Camera::get_state(uint8_t instance, camera_state_t& cam_state)
|
2023-04-07 23:35:51 -03:00
|
|
|
{
|
2023-04-11 21:11:26 -03:00
|
|
|
WITH_SEMAPHORE(_rsem);
|
|
|
|
|
2023-04-07 23:35:51 -03:00
|
|
|
auto *backend = get_instance(instance);
|
|
|
|
if (backend == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return backend->get_state(cam_state);
|
|
|
|
}
|
|
|
|
#endif // #if AP_CAMERA_SCRIPTING_ENABLED
|
|
|
|
|
2023-03-06 17:41:41 -04:00
|
|
|
// return backend for instance number
|
2023-04-07 23:33:22 -03:00
|
|
|
AP_Camera_Backend *AP_Camera::get_instance(uint8_t instance) const
|
2020-01-25 10:03:00 -04:00
|
|
|
{
|
2023-03-06 17:41:41 -04:00
|
|
|
if (instance >= ARRAY_SIZE(_backends)) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
return _backends[instance];
|
2020-01-25 10:03:00 -04:00
|
|
|
}
|
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// perform any required parameter conversion
|
|
|
|
void AP_Camera::convert_params()
|
2017-07-25 23:45:20 -03:00
|
|
|
{
|
2023-02-10 20:27:39 -04:00
|
|
|
// exit immediately if CAM1_TYPE has already been configured
|
|
|
|
if (_params[0].type.configured()) {
|
|
|
|
return;
|
2022-11-07 06:03:43 -04:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
|
2023-04-14 21:30:33 -03:00
|
|
|
// PARAMETER_CONVERSION - Added: Feb-2023 ahead of 4.4 release
|
2023-02-10 20:27:39 -04:00
|
|
|
|
|
|
|
// convert CAM_TRIGG_TYPE to CAM1_TYPE
|
|
|
|
int8_t cam_trigg_type = 0;
|
|
|
|
int8_t cam1_type = 0;
|
|
|
|
IGNORE_RETURN(AP_Param::get_param_by_index(this, 0, AP_PARAM_INT8, &cam_trigg_type));
|
|
|
|
if ((cam_trigg_type == 0) && SRV_Channels::function_assigned(SRV_Channel::k_cam_trigger)) {
|
|
|
|
// CAM_TRIGG_TYPE was 0 (Servo) and camera trigger servo function was assigned so set CAM1_TYPE = 1 (Servo)
|
|
|
|
cam1_type = 1;
|
2017-07-25 23:45:20 -03:00
|
|
|
}
|
2023-02-10 20:27:39 -04:00
|
|
|
if ((cam_trigg_type >= 1) && (cam_trigg_type <= 3)) {
|
|
|
|
// CAM_TRIGG_TYPE was set to Relay, GoPro or Mount
|
|
|
|
cam1_type = cam_trigg_type + 1;
|
|
|
|
}
|
|
|
|
_params[0].type.set_and_save(cam1_type);
|
2018-04-14 01:03:29 -03:00
|
|
|
|
2023-02-10 20:27:39 -04:00
|
|
|
// convert CAM_DURATION (in deci-seconds) to CAM1_DURATION (in seconds)
|
|
|
|
int8_t cam_duration = 0;
|
|
|
|
if (AP_Param::get_param_by_index(this, 1, AP_PARAM_INT8, &cam_duration) && (cam_duration > 0)) {
|
|
|
|
_params[0].trigger_duration.set_and_save(cam_duration * 0.1);
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert CAM_MIN_INTERVAL (in milliseconds) to CAM1__INTRVAL_MIN (in seconds)
|
|
|
|
int16_t cam_min_interval = 0;
|
|
|
|
if (AP_Param::get_param_by_index(this, 6, AP_PARAM_INT16, &cam_min_interval) && (cam_min_interval > 0)) {
|
|
|
|
_params[0].interval_min.set_and_save(cam_min_interval * 0.001f);
|
|
|
|
}
|
|
|
|
|
|
|
|
// find Camera's top level key
|
|
|
|
uint16_t k_param_camera_key;
|
|
|
|
if (!AP_Param::find_top_level_key_by_pointer(this, k_param_camera_key)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// table parameters to convert without scaling
|
|
|
|
static const AP_Param::ConversionInfo camera_param_conversion_info[] {
|
|
|
|
{ k_param_camera_key, 2, AP_PARAM_INT16, "CAM1_SERVO_ON" },
|
|
|
|
{ k_param_camera_key, 3, AP_PARAM_INT16, "CAM1_SERVO_OFF" },
|
|
|
|
{ k_param_camera_key, 4, AP_PARAM_FLOAT, "CAM1_TRIGG_DIST" },
|
|
|
|
{ k_param_camera_key, 5, AP_PARAM_INT8, "CAM1_RELAY_ON" },
|
|
|
|
{ k_param_camera_key, 8, AP_PARAM_INT8, "CAM1_FEEDBAK_PIN" },
|
|
|
|
{ k_param_camera_key, 9, AP_PARAM_INT8, "CAM1_FEEDBAK_POL" },
|
|
|
|
};
|
|
|
|
uint8_t table_size = ARRAY_SIZE(camera_param_conversion_info);
|
|
|
|
for (uint8_t i=0; i<table_size; i++) {
|
|
|
|
AP_Param::convert_old_parameter(&camera_param_conversion_info[i], 1.0f);
|
2022-09-26 09:06:45 -03:00
|
|
|
}
|
2020-02-15 20:27:08 -04:00
|
|
|
}
|
|
|
|
|
2018-04-14 01:03:29 -03:00
|
|
|
// singleton instance
|
|
|
|
AP_Camera *AP_Camera::_singleton;
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
|
|
|
|
AP_Camera *camera()
|
|
|
|
{
|
|
|
|
return AP_Camera::get_singleton();
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|
2022-06-02 05:28:26 -03:00
|
|
|
|
|
|
|
#endif
|