Browse Source

camera_trigger : clean up iterators

sbg
Mohammed Kabir 8 years ago committed by Lorenz Meier
parent
commit
9be7ad5805
  1. 2
      src/drivers/camera_trigger/interfaces/src/camera_interface.h
  2. 10
      src/drivers/camera_trigger/interfaces/src/gpio.cpp
  3. 1
      src/drivers/camera_trigger/interfaces/src/gpio.h
  4. 3
      src/drivers/camera_trigger/interfaces/src/pwm.cpp
  5. 10
      src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp

2
src/drivers/camera_trigger/interfaces/src/camera_interface.h

@ -4,6 +4,8 @@
#pragma once #pragma once
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
class CameraInterface class CameraInterface
{ {
public: public:

10
src/drivers/camera_trigger/interfaces/src/gpio.cpp

@ -16,7 +16,7 @@ CameraInterfaceGPIO::CameraInterfaceGPIO():
param_get(_p_polarity, &_polarity); param_get(_p_polarity, &_polarity);
// Set all pins as invalid // Set all pins as invalid
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
_pins[i] = -1; _pins[i] = -1;
} }
@ -28,7 +28,7 @@ CameraInterfaceGPIO::CameraInterfaceGPIO():
_pins[i] = single_pin - 1; _pins[i] = single_pin - 1;
if (_pins[i] < 0 || _pins[i] >= static_cast<int>(sizeof(_gpios) / sizeof(_gpios[0]))) { if (_pins[i] < 0 || _pins[i] >= static_cast<int>(arraySize(_gpios))) {
_pins[i] = -1; _pins[i] = -1;
} }
@ -45,7 +45,7 @@ CameraInterfaceGPIO::~CameraInterfaceGPIO()
void CameraInterfaceGPIO::setup() void CameraInterfaceGPIO::setup()
{ {
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
px4_arch_configgpio(_gpios[_pins[i]]); px4_arch_configgpio(_gpios[_pins[i]]);
px4_arch_gpiowrite(_gpios[_pins[i]], !_polarity); px4_arch_gpiowrite(_gpios[_pins[i]], !_polarity);
} }
@ -54,7 +54,7 @@ void CameraInterfaceGPIO::setup()
void CameraInterfaceGPIO::trigger(bool enable) void CameraInterfaceGPIO::trigger(bool enable)
{ {
if (enable) { if (enable) {
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
if (_pins[i] >= 0) { if (_pins[i] >= 0) {
// ACTIVE_LOW == 1 // ACTIVE_LOW == 1
px4_arch_gpiowrite(_gpios[_pins[i]], _polarity); px4_arch_gpiowrite(_gpios[_pins[i]], _polarity);
@ -62,7 +62,7 @@ void CameraInterfaceGPIO::trigger(bool enable)
} }
} else { } else {
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
if (_pins[i] >= 0) { if (_pins[i] >= 0) {
// ACTIVE_LOW == 1 // ACTIVE_LOW == 1
px4_arch_gpiowrite(_gpios[_pins[i]], !_polarity); px4_arch_gpiowrite(_gpios[_pins[i]], !_polarity);

1
src/drivers/camera_trigger/interfaces/src/gpio.h

@ -15,7 +15,6 @@
#include "camera_interface.h" #include "camera_interface.h"
class CameraInterfaceGPIO : public CameraInterface class CameraInterfaceGPIO : public CameraInterface
{ {
public: public:

3
src/drivers/camera_trigger/interfaces/src/pwm.cpp

@ -18,7 +18,7 @@ CameraInterfacePWM::CameraInterfacePWM():
param_get(_p_pin, &pin_list); param_get(_p_pin, &pin_list);
// Set all pins as invalid // Set all pins as invalid
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
_pins[i] = -1; _pins[i] = -1;
} }
@ -82,7 +82,6 @@ void CameraInterfacePWM::trigger(bool enable)
void CameraInterfacePWM::info() void CameraInterfacePWM::info()
{ {
// TODO : cleanup this output for all trigger types
PX4_INFO("PWM trigger mode (generic), pins enabled : [%d][%d][%d][%d][%d][%d]", PX4_INFO("PWM trigger mode (generic), pins enabled : [%d][%d][%d][%d][%d][%d]",
_pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0]); _pins[5], _pins[4], _pins[3], _pins[2], _pins[1], _pins[0]);
} }

10
src/drivers/camera_trigger/interfaces/src/seagull_map2.cpp

@ -28,7 +28,7 @@ CameraInterfaceSeagull::CameraInterfaceSeagull():
param_get(_p_pin, &pin_list); param_get(_p_pin, &pin_list);
// Set all pins as invalid // Set all pins as invalid
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i++) { for (unsigned i = 0; i < arraySize(_pins); i++) {
_pins[i] = -1; _pins[i] = -1;
} }
@ -59,7 +59,7 @@ CameraInterfaceSeagull::~CameraInterfaceSeagull()
void CameraInterfaceSeagull::setup() void CameraInterfaceSeagull::setup()
{ {
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i = i + 2) { for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
if (_pins[i] >= 0 && _pins[i + 1] >= 0) { if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
uint8_t pin_bitmask = (1 << _pins[i + 1]) | (1 << _pins[i]); uint8_t pin_bitmask = (1 << _pins[i + 1]) | (1 << _pins[i]);
up_pwm_trigger_init(pin_bitmask); up_pwm_trigger_init(pin_bitmask);
@ -76,7 +76,7 @@ void CameraInterfaceSeagull::trigger(bool enable)
return; return;
} }
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i = i + 2) { for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
if (_pins[i] >= 0 && _pins[i + 1] >= 0) { if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
// Set all valid pins to shoot or neutral levels // Set all valid pins to shoot or neutral levels
up_pwm_trigger_set(_pins[i + 1], math::constrain(enable ? PWM_CAMERA_INSTANT_SHOOT : PWM_CAMERA_NEUTRAL, 1000, 2000)); up_pwm_trigger_set(_pins[i + 1], math::constrain(enable ? PWM_CAMERA_INSTANT_SHOOT : PWM_CAMERA_NEUTRAL, 1000, 2000));
@ -92,7 +92,7 @@ void CameraInterfaceSeagull::keep_alive(bool signal_on)
return; return;
} }
for (unsigned i = 0; i < sizeof(_pins) / sizeof(_pins[0]); i = i + 2) { for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
if (_pins[i] >= 0 && _pins[i + 1] >= 0) { if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
// Set channel 2 pin to keep_alive or netural signal // Set channel 2 pin to keep_alive or netural signal
up_pwm_trigger_set(_pins[i], math::constrain(signal_on ? PWM_2_CAMERA_KEEP_ALIVE : PWM_CAMERA_NEUTRAL, 1000, 2000)); up_pwm_trigger_set(_pins[i], math::constrain(signal_on ? PWM_2_CAMERA_KEEP_ALIVE : PWM_CAMERA_NEUTRAL, 1000, 2000));
@ -103,7 +103,7 @@ void CameraInterfaceSeagull::keep_alive(bool signal_on)
void CameraInterfaceSeagull::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) { for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
if (_pins[i] >= 0 && _pins[i + 1] >= 0) { if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
// For now, set channel one to neutral upon startup. // For now, set channel one to neutral upon startup.
up_pwm_trigger_set(_pins[i + 1], math::constrain(PWM_CAMERA_NEUTRAL, 1000, 2000)); up_pwm_trigger_set(_pins[i + 1], math::constrain(PWM_CAMERA_NEUTRAL, 1000, 2000));

Loading…
Cancel
Save