Browse Source

camera_trigger : rename Seagull MAP2 interface

sbg
Mohammed Kabir 8 years ago committed by Lorenz Meier
parent
commit
c06d1a9dbe
  1. 2
      src/drivers/camera_trigger/CMakeLists.txt
  2. 13
      src/drivers/camera_trigger/camera_trigger.cpp
  3. 20
      src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp
  4. 10
      src/drivers/camera_trigger/interfaces/src/seagull_map2.h

2
src/drivers/camera_trigger/CMakeLists.txt

@ -38,7 +38,7 @@ px4_add_module( @@ -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

13
src/drivers/camera_trigger/camera_trigger.cpp

@ -1,6 +1,6 @@ @@ -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 @@ @@ -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 <mhkabir98@gmail.com>
* @author Mohammed Kabir <kabir@uasys.io>
* @author Kelly Steich <kelly.steich@wingtra.com>
* @author Andreas Bircher <andreas@wingtra.com>
*/
@ -66,7 +65,7 @@ @@ -66,7 +65,7 @@
#include <board_config.h>
#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() : @@ -257,7 +256,7 @@ CameraTrigger::CameraTrigger() :
break;
case CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM:
_camera_interface = new CameraInterfacePWM();
_camera_interface = new CameraInterfaceSeagull();
break;
#endif

20
src/drivers/camera_trigger/interfaces/src/pwm.cpp → src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp

@ -4,9 +4,9 @@ @@ -4,9 +4,9 @@
#include <lib/mathlib/mathlib.h>
#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 @@ @@ -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(): @@ -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() @@ -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) @@ -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) @@ -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) @@ -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]);
}

10
src/drivers/camera_trigger/interfaces/src/pwm.h → src/drivers/camera_trigger/interfaces/src/seagull_map2.h

@ -1,7 +1,7 @@ @@ -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 @@ @@ -15,11 +15,11 @@
#include <uORB/topics/vehicle_status.h>
#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);
Loading…
Cancel
Save