diff --git a/src/drivers/camera_trigger/CMakeLists.txt b/src/drivers/camera_trigger/CMakeLists.txt index 47211aded7..e72ebba712 100644 --- a/src/drivers/camera_trigger/CMakeLists.txt +++ b/src/drivers/camera_trigger/CMakeLists.txt @@ -38,7 +38,7 @@ px4_add_module( SRCS camera_trigger.cpp interfaces/src/camera_interface.cpp - interfaces/src/pwm.cpp + interfaces/src/seagull_map2.cpp interfaces/src/gpio.cpp DEPENDS platforms__common diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index f3c60da611..20b074f58e 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2015-2016 PX4 Development Team. All rights reserved. + * Copyright (c) 2015-2017 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,11 +34,10 @@ /** * @file camera_trigger.cpp * - * External camera-IMU synchronisation and triggering via FMU auxiliary pins. + * External camera-IMU synchronisation and triggering, and support for + * camera manipulation using PWM signals over FMU auxillary pins. * - * Support for camera manipulation via PWM signal over servo pins. - * - * @author Mohammed Kabir + * @author Mohammed Kabir * @author Kelly Steich * @author Andreas Bircher */ @@ -66,7 +65,7 @@ #include #include "interfaces/src/camera_interface.h" -#include "interfaces/src/pwm.h" +#include "interfaces/src/seagull_map2.h" #include "interfaces/src/gpio.h" #define TRIGGER_PIN_DEFAULT 1 @@ -257,7 +256,7 @@ CameraTrigger::CameraTrigger() : break; case CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM: - _camera_interface = new CameraInterfacePWM(); + _camera_interface = new CameraInterfaceSeagull(); break; #endif diff --git a/src/drivers/camera_trigger/interfaces/src/pwm.cpp b/src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp similarity index 84% rename from src/drivers/camera_trigger/interfaces/src/pwm.cpp rename to src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp index 31d33ced87..3837129f76 100644 --- a/src/drivers/camera_trigger/interfaces/src/pwm.cpp +++ b/src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp @@ -4,9 +4,9 @@ #include #include "drivers/drv_pwm_trigger.h" -#include "pwm.h" +#include "seagull_map2.h" -// PWM levels of the interface to seagull MAP converter to +// PWM levels of the interface to Seagull MAP 2 converter to // Multiport (http://www.seagulluav.com/manuals/Seagull_MAP2-Manual.pdf) #define PWM_CAMERA_DISARMED 900 #define PWM_CAMERA_ON 1100 @@ -17,7 +17,7 @@ #define PWM_2_CAMERA_KEEP_ALIVE 1700 #define PWM_2_CAMERA_ON_OFF 1900 -CameraInterfacePWM::CameraInterfacePWM(): +CameraInterfaceSeagull::CameraInterfaceSeagull(): CameraInterface(), _camera_is_on(false) { @@ -49,13 +49,13 @@ CameraInterfacePWM::CameraInterfacePWM(): setup(); } -CameraInterfacePWM::~CameraInterfacePWM() +CameraInterfaceSeagull::~CameraInterfaceSeagull() { // Deinitialise pwm channels up_pwm_trigger_deinit(); } -void CameraInterfacePWM::setup() +void CameraInterfaceSeagull::setup() { for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i = i + 2) { if (_pins[i] >= 0 && _pins[i + 1] >= 0) { @@ -67,7 +67,7 @@ void CameraInterfacePWM::setup() } } -void CameraInterfacePWM::trigger(bool enable) +void CameraInterfaceSeagull::trigger(bool enable) { // This only starts working upon prearming @@ -83,7 +83,7 @@ void CameraInterfacePWM::trigger(bool enable) } } -void CameraInterfacePWM::keep_alive(bool signal_on) +void CameraInterfaceSeagull::keep_alive(bool signal_on) { // This should alternate between signal_on and !signal_on to keep the camera alive @@ -99,7 +99,7 @@ void CameraInterfacePWM::keep_alive(bool signal_on) } } -void CameraInterfacePWM::turn_on_off(bool enable) +void CameraInterfaceSeagull::turn_on_off(bool enable) { for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i = i + 2) { @@ -113,9 +113,9 @@ void CameraInterfacePWM::turn_on_off(bool enable) if (!enable) { _camera_is_on = !_camera_is_on; } } -void CameraInterfacePWM::info() +void CameraInterfaceSeagull::info() { - PX4_INFO("PWM trigger mode, pins enabled : [%d][%d][%d][%d][%d][%d]", + PX4_INFO("PWM trigger mode (Seagull MAP2) , pins enabled : [%d][%d][%d][%d][%d][%d]", _pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0]); } diff --git a/src/drivers/camera_trigger/interfaces/src/pwm.h b/src/drivers/camera_trigger/interfaces/src/seagull_map2.h similarity index 68% rename from src/drivers/camera_trigger/interfaces/src/pwm.h rename to src/drivers/camera_trigger/interfaces/src/seagull_map2.h index 5f2c0fb320..e409998a7e 100644 --- a/src/drivers/camera_trigger/interfaces/src/pwm.h +++ b/src/drivers/camera_trigger/interfaces/src/seagull_map2.h @@ -1,7 +1,7 @@ /** - * @file pwm.h + * @file seagull_map2.h * - * Interface with cameras via pwm. + * Interface supported cameras using a Seagull MAP2 interface. * */ #pragma once @@ -15,11 +15,11 @@ #include #include "camera_interface.h" -class CameraInterfacePWM : public CameraInterface +class CameraInterfaceSeagull : public CameraInterface { public: - CameraInterfacePWM(); - virtual ~CameraInterfacePWM(); + CameraInterfaceSeagull(); + virtual ~CameraInterfaceSeagull(); void trigger(bool enable); void keep_alive(bool signal_on);