mirror of
https://gitee.com/xiaohuolufeihua/bizhang_-obav.git
synced 2026-05-21 01:12:11 +00:00
camera_trigger : rename relay to gpio
This commit is contained in:
committed by
Lorenz Meier
parent
95778c74e2
commit
2b838f5704
@@ -39,7 +39,7 @@ px4_add_module(
|
||||
camera_trigger.cpp
|
||||
interfaces/src/camera_interface.cpp
|
||||
interfaces/src/pwm.cpp
|
||||
interfaces/src/relay.cpp
|
||||
interfaces/src/gpio.cpp
|
||||
DEPENDS
|
||||
platforms__common
|
||||
)
|
||||
|
||||
@@ -67,7 +67,7 @@
|
||||
|
||||
#include "interfaces/src/camera_interface.h"
|
||||
#include "interfaces/src/pwm.h"
|
||||
#include "interfaces/src/relay.h"
|
||||
#include "interfaces/src/gpio.h"
|
||||
|
||||
#define TRIGGER_PIN_DEFAULT 1
|
||||
|
||||
@@ -75,7 +75,7 @@ extern "C" __EXPORT int camera_trigger_main(int argc, char *argv[]);
|
||||
|
||||
typedef enum : int32_t {
|
||||
CAMERA_INTERFACE_MODE_NONE = 0,
|
||||
CAMERA_INTERFACE_MODE_RELAY,
|
||||
CAMERA_INTERFACE_MODE_GPIO,
|
||||
CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM,
|
||||
CAMERA_INTERFACE_MODE_MAVLINK
|
||||
} camera_interface_mode_t;
|
||||
@@ -224,7 +224,7 @@ CameraTrigger::CameraTrigger() :
|
||||
_vcommand_sub(-1),
|
||||
_vlposition_sub(-1),
|
||||
_trigger_pub(nullptr),
|
||||
_camera_interface_mode(CAMERA_INTERFACE_MODE_RELAY),
|
||||
_camera_interface_mode(CAMERA_INTERFACE_MODE_GPIO),
|
||||
_camera_interface(nullptr)
|
||||
{
|
||||
//Initiate Camera interface basedon camera_interface_mode
|
||||
@@ -252,8 +252,8 @@ CameraTrigger::CameraTrigger() :
|
||||
switch (_camera_interface_mode) {
|
||||
#ifdef __PX4_NUTTX
|
||||
|
||||
case CAMERA_INTERFACE_MODE_RELAY:
|
||||
_camera_interface = new CameraInterfaceRelay();
|
||||
case CAMERA_INTERFACE_MODE_GPIO:
|
||||
_camera_interface = new CameraInterfaceGPIO();
|
||||
break;
|
||||
|
||||
case CAMERA_INTERFACE_MODE_SEAGULL_MAP2_PWM:
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
#ifdef __PX4_NUTTX
|
||||
#include "relay.h"
|
||||
#include "gpio.h"
|
||||
|
||||
constexpr uint32_t CameraInterfaceRelay::_gpios[6];
|
||||
constexpr uint32_t CameraInterfaceGPIO::_gpios[6];
|
||||
|
||||
CameraInterfaceRelay::CameraInterfaceRelay():
|
||||
CameraInterfaceGPIO::CameraInterfaceGPIO():
|
||||
CameraInterface(),
|
||||
_pins{},
|
||||
_polarity(0)
|
||||
@@ -39,11 +39,11 @@ CameraInterfaceRelay::CameraInterfaceRelay():
|
||||
setup();
|
||||
}
|
||||
|
||||
CameraInterfaceRelay::~CameraInterfaceRelay()
|
||||
CameraInterfaceGPIO::~CameraInterfaceGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void CameraInterfaceRelay::setup()
|
||||
void CameraInterfaceGPIO::setup()
|
||||
{
|
||||
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) {
|
||||
px4_arch_configgpio(_gpios[_pins[i]]);
|
||||
@@ -51,7 +51,7 @@ void CameraInterfaceRelay::setup()
|
||||
}
|
||||
}
|
||||
|
||||
void CameraInterfaceRelay::trigger(bool enable)
|
||||
void CameraInterfaceGPIO::trigger(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) {
|
||||
@@ -71,9 +71,10 @@ void CameraInterfaceRelay::trigger(bool enable)
|
||||
}
|
||||
}
|
||||
|
||||
void CameraInterfaceRelay::info()
|
||||
void CameraInterfaceGPIO::info()
|
||||
{
|
||||
warnx("Relay - camera triggering, pins 1-3 : %d,%d,%d polarity : %s", _pins[0], _pins[1], _pins[2],
|
||||
warnx("GPIO trigger mode, AUX pin state 1-6 : [%d][%d][%d][%d][%d][%d], polarity : %s",
|
||||
_pins[0], _pins[1], _pins[2], _pins[3], _pins[4], _pins[5],
|
||||
_polarity ? "ACTIVE_HIGH" : "ACTIVE_LOW");
|
||||
}
|
||||
|
||||
@@ -15,11 +15,11 @@
|
||||
#include "camera_interface.h"
|
||||
|
||||
|
||||
class CameraInterfaceRelay : public CameraInterface
|
||||
class CameraInterfaceGPIO : public CameraInterface
|
||||
{
|
||||
public:
|
||||
CameraInterfaceRelay();
|
||||
virtual ~CameraInterfaceRelay();
|
||||
CameraInterfaceGPIO();
|
||||
virtual ~CameraInterfaceGPIO();
|
||||
|
||||
void trigger(bool enable);
|
||||
|
||||
Reference in New Issue
Block a user