Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Camera: runcam backend #26887

Draft
wants to merge 9 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion Tools/scripts/build_options.py
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ def config_option(self):
Feature('Camera', 'Camera_FOV_Status', 'AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'Enable Camera FOV Status send to GCS', 0, 'Camera,MOUNT'), # noqa: E501
Feature('Camera', 'Camera_ThermalRange', 'AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'Enable Camera Thermal Range send to GCS', 0, 'Camera,MOUNT'), # noqa: E501

Feature('Camera', 'RUNCAM', 'HAL_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None),
Feature('Camera', 'RUNCAM', 'AP_CAMERA_RUNCAM_ENABLED', 'Enable RunCam Control', 0, None),

Feature('Copter', 'MODE_ZIGZAG', 'MODE_ZIGZAG_ENABLED', 'Enable Mode ZigZag', 0, None),
Feature('Copter', 'MODE_SYSTEMID', 'MODE_SYSTEMID_ENABLED', 'Enable Mode SystemID', 0, 'Logging'),
Expand Down
2 changes: 1 addition & 1 deletion Tools/scripts/extract_features.py
Original file line number Diff line number Diff line change
Expand Up @@ -137,7 +137,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"):
('AP_CAMERA_{type}_ENABLED', 'AP_Camera_(?P<type>.*)::trigger_pic',),
('AP_CAMERA_SEND_FOV_STATUS_ENABLED', 'AP_Camera::send_camera_fov_status'),
('AP_CAMERA_SEND_THERMAL_RANGE_ENABLED', 'AP_Camera::send_camera_thermal_range'),
('HAL_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),
('AP_CAMERA_RUNCAM_ENABLED', 'AP_RunCam::AP_RunCam',),

('HAL_PROXIMITY_ENABLED', 'AP_Proximity::AP_Proximity',),
('AP_PROXIMITY_{type}_ENABLED', 'AP_Proximity_(?P<type>.*)::update',),
Expand Down
6 changes: 3 additions & 3 deletions libraries/AP_Arming/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1292,7 +1292,7 @@ bool AP_Arming::fence_checks(bool display_failure)
}
#endif // AP_FENCE_ENABLED

#if HAL_RUNCAM_ENABLED
#if AP_CAMERA_RUNCAM_ENABLED
bool AP_Arming::camera_checks(bool display_failure)
{
if (check_enabled(ARMING_CHECK_CAMERA)) {
Expand All @@ -1310,7 +1310,7 @@ bool AP_Arming::camera_checks(bool display_failure)
}
return true;
}
#endif // HAL_RUNCAM_ENABLED
#endif // AP_CAMERA_RUNCAM_ENABLED

#if OSD_ENABLED
bool AP_Arming::osd_checks(bool display_failure) const
Expand Down Expand Up @@ -1604,7 +1604,7 @@ bool AP_Arming::pre_arm_checks(bool report)
#if HAL_PROXIMITY_ENABLED
& proximity_checks(report)
#endif
#if HAL_RUNCAM_ENABLED
#if AP_CAMERA_RUNCAM_ENABLED
& camera_checks(report)
#endif
#if OSD_ENABLED
Expand Down
48 changes: 47 additions & 1 deletion libraries/AP_Camera/AP_Camera.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AP_Vehicle/AP_Vehicle.h>
#include "AP_Camera_Backend.h"
#include "AP_Camera_Servo.h"
#include "AP_Camera_Relay.h"
Expand All @@ -14,6 +15,7 @@
#include "AP_Camera_MAVLink.h"
#include "AP_Camera_MAVLinkCamV2.h"
#include "AP_Camera_Scripting.h"
#include "AP_RunCam.h"

const AP_Param::GroupInfo AP_Camera::var_info[] = {

Expand Down Expand Up @@ -42,9 +44,21 @@ const AP_Param::GroupInfo AP_Camera::var_info[] = {
AP_SUBGROUPINFO(_params[1], "2", 13, AP_Camera, AP_Camera_Params),
#endif

// @Group: 1_RC_
// @Path: AP_RunCam.cpp
AP_SUBGROUPVARPTR(_backends[0], "1_RC_", 14, AP_Camera, _backend_var_info[0]),

#if AP_CAMERA_MAX_INSTANCES > 1
// @Group: 2_RC2_
// @Path: AP_RunCam.cpp
AP_SUBGROUPVARPTR(_backends[1], "2_RC2_", 15, AP_Camera, _backend_var_info[1]),
#endif

AP_GROUPEND
};

const AP_Param::GroupInfo *AP_Camera::_backend_var_info[AP_CAMERA_MAX_INSTANCES];

extern const AP_HAL::HAL& hal;

AP_Camera::AP_Camera(uint32_t _log_camera_bit) :
Expand Down Expand Up @@ -238,6 +252,15 @@ void AP_Camera::init()
case CameraType::SCRIPTING:
_backends[instance] = NEW_NOTHROW AP_Camera_Scripting(*this, _params[instance], instance);
break;
#endif
#if AP_CAMERA_RUNCAM_ENABLED
// check for Scripting driver
case CameraType::RUNCAM:
_backends[instance] = NEW_NOTHROW AP_RunCam(*this, _params[instance], instance);
_backend_var_info[instance] = AP_RunCam::var_info;
AP_Param::load_object_from_eeprom(_backends[instance], _backend_var_info[instance]);
AP_Param::invalidate_count();
break;
#endif
case CameraType::NONE:
break;
Expand Down Expand Up @@ -830,7 +853,7 @@ void AP_Camera::convert_params()
{
// exit immediately if CAM1_TYPE has already been configured
if (_params[0].type.configured()) {
return;
//return;
}

// PARAMETER_CONVERSION - Added: Feb-2023 ahead of 4.4 release
Expand All @@ -847,6 +870,29 @@ void AP_Camera::convert_params()
// CAM_TRIGG_TYPE was set to Relay, GoPro or Mount
cam1_type = cam_trigg_type + 1;
}
#if AP_CAMERA_RUNCAM_ENABLED
// find vehicle's top level key
uint16_t k_param_vehicle_key;
if (!AP_Param::find_top_level_key_by_pointer(AP::vehicle(), k_param_vehicle_key)) {
return;
}

const AP_Param::ConversionInfo rc_type_info = {k_param_vehicle_key, 1, AP_PARAM_INT8, "CAM_RC_TYPE"};
AP_Int8 rc_type_old;
const bool found_rc_type = AP_Param::find_old_parameter(&rc_type_info, &rc_type_old);

if (found_rc_type && rc_type_old.get() > 0) {
_backends[0] = NEW_NOTHROW AP_RunCam(*this, _params[0], 0);
_backend_var_info[0] = AP_RunCam::var_info;
AP_Param::convert_class(k_param_vehicle_key, &_backends[0], _backend_var_info[0], 1, false);
}

// RunCam protocol configured so set cam type to RunCam
AP_SerialManager *serial_manager = AP_SerialManager::get_singleton();
if (serial_manager && serial_manager->find_serial(AP_SerialManager::SerialProtocol_RunCam, 0)) {
cam1_type = uint8_t(CameraType::RUNCAM);
}
#endif
_params[0].type.set_and_save(cam1_type);

// convert CAM_DURATION (in deci-seconds) to CAM1_DURATION (in seconds)
Expand Down
6 changes: 6 additions & 0 deletions libraries/AP_Camera/AP_Camera.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@ class AP_Camera_Mount;
class AP_Camera_MAVLink;
class AP_Camera_MAVLinkCamV2;
class AP_Camera_Scripting;
class AP_RunCam;

/// @class Camera
/// @brief Object managing a Photo or video camera
Expand All @@ -37,6 +38,7 @@ class AP_Camera {
friend class AP_Camera_MAVLink;
friend class AP_Camera_MAVLinkCamV2;
friend class AP_Camera_Scripting;
friend class AP_RunCam;

public:

Expand Down Expand Up @@ -72,6 +74,9 @@ class AP_Camera {
#endif
#if AP_CAMERA_SCRIPTING_ENABLED
SCRIPTING = 7, // Scripting backend
#endif
#if AP_CAMERA_RUNCAM_ENABLED
RUNCAM = 8, // RunCam backend
#endif
};

Expand Down Expand Up @@ -208,6 +213,7 @@ class AP_Camera {

// parameters for backends
AP_Camera_Params _params[AP_CAMERA_MAX_INSTANCES];
static const struct AP_Param::GroupInfo *_backend_var_info[AP_CAMERA_MAX_INSTANCES];

private:

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Camera/AP_Camera_Params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
// @Param: _TYPE
// @DisplayName: Camera shutter (trigger) type
// @Description: how to trigger the camera to take a picture
// @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi/Topotek/Viewpro/Xacti), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting
// @Values: 0:None, 1:Servo, 2:Relay, 3:GoPro in Solo Gimbal, 4:Mount (Siyi/Topotek/Viewpro/Xacti), 5:MAVLink, 6:MAVLinkCamV2, 7:Scripting, 8:RunCam
// @User: Standard
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_Camera_Params, type, 0, AP_PARAM_FLAG_ENABLE),

Expand Down
4 changes: 4 additions & 0 deletions libraries/AP_Camera/AP_Camera_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -58,3 +58,7 @@
#ifndef HAL_RUNCAM_ENABLED
#define HAL_RUNCAM_ENABLED 1
#endif

#ifndef AP_CAMERA_RUNCAM_ENABLED
#define AP_CAMERA_RUNCAM_ENABLED AP_CAMERA_BACKEND_DEFAULT_ENABLED && HAL_RUNCAM_ENABLED
#endif
48 changes: 42 additions & 6 deletions libraries/AP_Camera/AP_RunCam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
*/
#include "AP_RunCam.h"

#if HAL_RUNCAM_ENABLED
#if AP_CAMERA_RUNCAM_ENABLED

#include <AP_Math/AP_Math.h>
#include <AP_Math/crc.h>
Expand All @@ -36,7 +36,7 @@ const AP_Param::GroupInfo AP_RunCam::var_info[] = {
// @DisplayName: RunCam device type
// @Description: RunCam device type used to determine OSD menu structure and shutter options.
// @Values: 0:Disabled, 1:RunCam Split Micro/RunCam with UART, 2:RunCam Split, 3:RunCam Split4 4k, 4:RunCam Hybrid/RunCam Thumb Pro, 5:Runcam 2 4k
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::Disabled), AP_PARAM_FLAG_ENABLE),
AP_GROUPINFO_FLAGS("TYPE", 1, AP_RunCam, _cam_type, int(DeviceType::SplitMicro), AP_PARAM_FLAG_ENABLE),

// @Param: FEATURES
// @DisplayName: RunCam features available
Expand Down Expand Up @@ -118,13 +118,16 @@ AP_RunCam::Menu AP_RunCam::_menus[RUNCAM_MAX_DEVICE_TYPES] = {
{ 6, { 3, 10, 2, 2, 8 }}, // Runcam 2 4K
};

AP_RunCam::AP_RunCam()
AP_RunCam::AP_RunCam(AP_Camera &frontend, AP_Camera_Params &params, uint8_t instance)
: AP_Camera_Backend(frontend, params, instance)
{
AP_Param::setup_object_defaults(this, var_info);
if (_singleton != nullptr) {
if (_singleton != nullptr && _singleton->_instance == instance) {
AP_HAL::panic("AP_RunCam must be singleton");
}
_singleton = this;
if (_singleton == nullptr) {
_singleton = this;
}
_cam_type.set(constrain_int16(_cam_type, 0, RUNCAM_MAX_DEVICE_TYPES));
_video_recording = VideoOption(_cam_control_option & uint8_t(ControlOption::VIDEO_RECORDING_AT_BOOT));
}
Expand Down Expand Up @@ -1058,8 +1061,41 @@ uint8_t AP_RunCam::Request::get_expected_response_length(const Command command)
return 0;
}

// AP_Camera API

// return true if healthy
bool AP_RunCam::healthy() const
{
return true;
}

// momentary switch to change camera between picture and video modes
void AP_RunCam::cam_mode_toggle() {

}

// entry point to actually take a picture. returns true on success
bool AP_RunCam::trigger_pic() {
return false;
}

// send camera information message to GCS
void AP_RunCam::send_camera_information(mavlink_channel_t chan) const
{
}

// send camera settings message to GCS
void AP_RunCam::send_camera_settings(mavlink_channel_t chan) const
{
}

// send camera capture status message to GCS
void AP_RunCam::send_camera_capture_status(mavlink_channel_t chan) const
{
}

AP_RunCam *AP::runcam() {
return AP_RunCam::get_singleton();
}

#endif // HAL_RUNCAM_ENABLED
#endif // AP_CAMERA_RUNCAM_ENABLED
46 changes: 39 additions & 7 deletions libraries/AP_Camera/AP_RunCam.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,9 @@

#include "AP_Camera_config.h"

#if HAL_RUNCAM_ENABLED
#include "AP_Camera_Backend.h"

#if AP_CAMERA_RUNCAM_ENABLED

#include <AP_Param/AP_Param.h>
#include <RC_Channel/RC_Channel.h>
Expand All @@ -39,10 +41,10 @@

/// @class AP_RunCam
/// @brief Object managing a RunCam device
class AP_RunCam
class AP_RunCam : public AP_Camera_Backend
{
public:
AP_RunCam();
AP_RunCam(AP_Camera &frontend, AP_Camera_Params &params, uint8_t instance);

// do not allow copies
CLASS_NO_COPY(AP_RunCam);
Expand Down Expand Up @@ -80,22 +82,52 @@ class AP_RunCam
VIDEO_RECORDING_AT_BOOT = (1 << 4)
};


// return true if healthy
bool healthy() const override;

// momentary switch to change camera between picture and video modes
void cam_mode_toggle() override;

// entry point to actually take a picture. returns true on success
bool trigger_pic() override;

// send camera information message to GCS
void send_camera_information(mavlink_channel_t chan) const override;

// send camera settings message to GCS
void send_camera_settings(mavlink_channel_t chan) const override;

// send camera capture status message to GCS
void send_camera_capture_status(mavlink_channel_t chan) const override;

// initialize the RunCam driver
void init();
void init() override;
// camera button simulation
bool simulate_camera_button(const ControlOperation operation, const uint32_t transition_timeout = RUNCAM_DEFAULT_BUTTON_PRESS_DELAY);
// start the video
void start_recording();
// stop the video
void stop_recording();
// start or stop video recording. returns true on success
// set start_recording = true to start record, false to stop recording
bool record_video(bool _start_recording) override {
if (_start_recording) {
start_recording();
} else {
stop_recording();
}
return true;
}

// enter the OSD menu
void enter_osd();
// exit the OSD menu
void exit_osd();
// OSD control determined by camera options
void osd_option();
// update loop
void update();
// update - should be called at 50hz
void update() override;
// Check whether arming is allowed
bool pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const;

Expand Down Expand Up @@ -436,4 +468,4 @@ namespace AP
AP_RunCam *runcam();
};

#endif // HAL_RUNCAM_ENABLED
#endif // AP_CAMERA_RUNCAM_ENABLED
11 changes: 0 additions & 11 deletions libraries/AP_Vehicle/AP_Vehicle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,11 +34,6 @@ extern AP_IOMCU iomcu;
2nd group of parameters
*/
const AP_Param::GroupInfo AP_Vehicle::var_info[] = {
#if HAL_RUNCAM_ENABLED
// @Group: CAM_RC_
// @Path: ../AP_Camera/AP_RunCam.cpp
AP_SUBGROUPINFO(runcam, "CAM_RC_", 1, AP_Vehicle, AP_RunCam),
#endif

#if HAL_GYROFFT_ENABLED
// @Group: FFT_
Expand Down Expand Up @@ -449,9 +444,6 @@ void AP_Vehicle::setup()
gyro_fft.init(1000);
#endif
#endif
#if HAL_RUNCAM_ENABLED
runcam.init();
#endif
#if HAL_HOTT_TELEM_ENABLED
hott_telem.init();
#endif
Expand Down Expand Up @@ -614,9 +606,6 @@ const AP_Scheduler::Task AP_Vehicle::scheduler_tasks[] = {
#if HAL_NMEA_OUTPUT_ENABLED
SCHED_TASK_CLASS(AP_NMEA_Output, &vehicle.nmea, update, 50, 50, 180),
#endif
#if HAL_RUNCAM_ENABLED
SCHED_TASK_CLASS(AP_RunCam, &vehicle.runcam, update, 50, 50, 200),
#endif
#if HAL_GYROFFT_ENABLED
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update, 400, 50, 205),
SCHED_TASK_CLASS(AP_GyroFFT, &vehicle.gyro_fft, update_parameters, 1, 50, 210),
Expand Down
Loading