forked from Archive/PX4-Autopilot
WIP hacks
This commit is contained in:
parent
d9c5032cd1
commit
71386aa46d
|
@ -34,6 +34,7 @@ px4_add_module(
|
|||
MODULE drivers__camera_trigger
|
||||
MAIN camera_trigger
|
||||
COMPILE_FLAGS
|
||||
-O0
|
||||
SRCS
|
||||
camera_trigger.cpp
|
||||
interfaces/src/camera_interface.cpp
|
||||
|
|
|
@ -1,20 +1,8 @@
|
|||
#include "camera_interface.h"
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
/**
|
||||
* @file camera_interface.cpp
|
||||
*
|
||||
*/
|
||||
|
||||
CameraInterface::CameraInterface():
|
||||
_p_pin(PARAM_INVALID),
|
||||
_pins{}
|
||||
{
|
||||
}
|
||||
|
||||
void CameraInterface::get_pins()
|
||||
{
|
||||
|
||||
// Get parameter handle
|
||||
_p_pin = param_find("TRIG_PINS");
|
||||
|
||||
|
|
|
@ -12,15 +12,7 @@
|
|||
class CameraInterface
|
||||
{
|
||||
public:
|
||||
|
||||
/**
|
||||
* Constructor
|
||||
*/
|
||||
CameraInterface();
|
||||
|
||||
/**
|
||||
* Destructor.
|
||||
*/
|
||||
CameraInterface() = default;
|
||||
virtual ~CameraInterface() = default;
|
||||
|
||||
/**
|
||||
|
@ -72,8 +64,8 @@ protected:
|
|||
*/
|
||||
void get_pins();
|
||||
|
||||
param_t _p_pin;
|
||||
param_t _p_pin{PARAM_INVALID};
|
||||
|
||||
int _pins[6];
|
||||
int _pins[6]{};
|
||||
|
||||
};
|
||||
|
|
|
@ -4,15 +4,12 @@
|
|||
#include <cstring>
|
||||
#include <px4_arch/io_timer.h>
|
||||
|
||||
CameraInterfaceGPIO::CameraInterfaceGPIO():
|
||||
CameraInterface(),
|
||||
_trigger_invert(false),
|
||||
_triggers{}
|
||||
CameraInterfaceGPIO::CameraInterfaceGPIO()
|
||||
{
|
||||
_p_polarity = param_find("TRIG_POLARITY");
|
||||
|
||||
// polarity of the trigger (0 = active low, 1 = active high )
|
||||
int32_t polarity;
|
||||
int32_t polarity = 0;
|
||||
param_get(_p_polarity, &polarity);
|
||||
_trigger_invert = (polarity == 0);
|
||||
|
||||
|
@ -23,7 +20,6 @@ CameraInterfaceGPIO::CameraInterfaceGPIO():
|
|||
void CameraInterfaceGPIO::setup()
|
||||
{
|
||||
for (unsigned i = 0, t = 0; i < arraySize(_pins); i++) {
|
||||
|
||||
// Pin range is from 0 to num_gpios - 1
|
||||
if (_pins[i] >= 0 && t < (int)arraySize(_triggers)) {
|
||||
uint32_t gpio = io_timer_channel_get_gpio_output(_pins[i]);
|
||||
|
@ -39,10 +35,9 @@ void CameraInterfaceGPIO::trigger(bool trigger_on_true)
|
|||
bool trigger_state = trigger_on_true ^ _trigger_invert;
|
||||
|
||||
for (unsigned i = 0; i < arraySize(_triggers); i++) {
|
||||
|
||||
if (_triggers[i] == 0) { break; }
|
||||
|
||||
px4_arch_gpiowrite(_triggers[i], trigger_state);
|
||||
if (_triggers[i] != 0) {
|
||||
px4_arch_gpiowrite(_triggers[i], trigger_state);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -27,11 +27,11 @@ private:
|
|||
|
||||
void setup();
|
||||
|
||||
param_t _p_polarity;
|
||||
param_t _p_polarity{PARAM_INVALID};
|
||||
|
||||
bool _trigger_invert;
|
||||
bool _trigger_invert{false};
|
||||
|
||||
uint32_t _triggers[num_gpios];
|
||||
uint32_t _triggers[num_gpios]{};
|
||||
};
|
||||
|
||||
#endif /* ifdef __PX4_NUTTX */
|
||||
|
|
|
@ -25,10 +25,10 @@ public:
|
|||
void info();
|
||||
|
||||
private:
|
||||
int32_t _pwm_camera_shoot = 0;
|
||||
int32_t _pwm_camera_neutral = 0;
|
||||
void setup();
|
||||
|
||||
int32_t _pwm_camera_shoot{0};
|
||||
int32_t _pwm_camera_neutral{0};
|
||||
};
|
||||
|
||||
#endif /* ifdef __PX4_NUTTX */
|
||||
|
|
|
@ -17,9 +17,7 @@
|
|||
#define PWM_2_CAMERA_KEEP_ALIVE 1700
|
||||
#define PWM_2_CAMERA_ON_OFF 1900
|
||||
|
||||
CameraInterfaceSeagull::CameraInterfaceSeagull():
|
||||
CameraInterface(),
|
||||
_camera_is_on(false)
|
||||
CameraInterfaceSeagull::CameraInterfaceSeagull()
|
||||
{
|
||||
//get_pins();
|
||||
|
||||
|
@ -80,9 +78,7 @@ void CameraInterfaceSeagull::trigger(bool trigger_on_true)
|
|||
|
||||
void CameraInterfaceSeagull::send_keep_alive(bool enable)
|
||||
{
|
||||
fprintf(stderr, "seagull keep alive %d (camera is on: %d)\n", enable, _camera_is_on);
|
||||
// This should alternate between enable and !enable to keep the camera alive
|
||||
|
||||
if (!_camera_is_on) {
|
||||
return;
|
||||
}
|
||||
|
@ -90,7 +86,6 @@ void CameraInterfaceSeagull::send_keep_alive(bool enable)
|
|||
for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
|
||||
if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
|
||||
// Set channel 2 pin to keep_alive or netural signal
|
||||
fprintf(stderr, "seagull keep alive pin %d %d\n", i, _pins[i]);
|
||||
up_pwm_trigger_set(_pins[i], enable ? PWM_2_CAMERA_KEEP_ALIVE : PWM_CAMERA_NEUTRAL);
|
||||
}
|
||||
}
|
||||
|
@ -98,9 +93,7 @@ void CameraInterfaceSeagull::send_keep_alive(bool enable)
|
|||
|
||||
void CameraInterfaceSeagull::send_toggle_power(bool enable)
|
||||
{
|
||||
fprintf(stderr, "seagull toggle power %d\n", enable);
|
||||
// This should alternate between enable and !enable to toggle camera power
|
||||
|
||||
for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
|
||||
if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
|
||||
// Set channel 1 to neutral
|
||||
|
@ -110,7 +103,9 @@ void CameraInterfaceSeagull::send_toggle_power(bool enable)
|
|||
}
|
||||
}
|
||||
|
||||
if (!enable) { _camera_is_on = !_camera_is_on; }
|
||||
if (!enable) {
|
||||
_camera_is_on = !_camera_is_on;
|
||||
}
|
||||
}
|
||||
|
||||
void CameraInterfaceSeagull::info()
|
||||
|
|
|
@ -33,7 +33,7 @@ public:
|
|||
private:
|
||||
void setup();
|
||||
|
||||
bool _camera_is_on;
|
||||
bool _camera_is_on{false};
|
||||
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue