forked from Archive/PX4-Autopilot
Rename trigger argument for clarity
This commit is contained in:
parent
4e5e0c6921
commit
afc8fe39df
|
@ -27,7 +27,7 @@ public:
|
|||
* trigger the camera
|
||||
* @param enable
|
||||
*/
|
||||
virtual void trigger(bool enable) {}
|
||||
virtual void trigger(bool trigger_on_true) {}
|
||||
|
||||
/**
|
||||
* send command to turn the camera on/off
|
||||
|
|
|
@ -18,7 +18,7 @@ public:
|
|||
CameraInterfaceGPIO();
|
||||
virtual ~CameraInterfaceGPIO();
|
||||
|
||||
void trigger(bool enable);
|
||||
void trigger(bool trigger_on_true);
|
||||
|
||||
void info();
|
||||
|
||||
|
|
|
@ -46,12 +46,12 @@ void CameraInterfacePWM::setup()
|
|||
|
||||
}
|
||||
|
||||
void CameraInterfacePWM::trigger(bool enable)
|
||||
void CameraInterfacePWM::trigger(bool trigger_on_true)
|
||||
{
|
||||
for (unsigned i = 0; i < arraySize(_pins); i++) {
|
||||
if (_pins[i] >= 0) {
|
||||
// Set all valid pins to shoot or neutral levels
|
||||
up_pwm_trigger_set(_pins[i], math::constrain(enable ? PWM_CAMERA_SHOOT : PWM_CAMERA_NEUTRAL, 1000, 2000));
|
||||
up_pwm_trigger_set(_pins[i], math::constrain(trigger_on_true ? PWM_CAMERA_SHOOT : PWM_CAMERA_NEUTRAL, 1000, 2000));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -20,7 +20,7 @@ public:
|
|||
CameraInterfacePWM();
|
||||
virtual ~CameraInterfacePWM();
|
||||
|
||||
void trigger(bool enable);
|
||||
void trigger(bool trigger_on_true);
|
||||
|
||||
void info();
|
||||
|
||||
|
|
|
@ -52,7 +52,7 @@ void CameraInterfaceSeagull::setup()
|
|||
PX4_ERR("Bad pin configuration - Seagull MAP2 requires 2 consecutive pins for control.");
|
||||
}
|
||||
|
||||
void CameraInterfaceSeagull::trigger(bool enable)
|
||||
void CameraInterfaceSeagull::trigger(bool trigger_on_true)
|
||||
{
|
||||
|
||||
if (!_camera_is_on) {
|
||||
|
@ -62,7 +62,7 @@ void CameraInterfaceSeagull::trigger(bool enable)
|
|||
for (unsigned i = 0; i < arraySize(_pins); i = i + 2) {
|
||||
if (_pins[i] >= 0 && _pins[i + 1] >= 0) {
|
||||
// Set channel 1 to shoot or neutral levels
|
||||
up_pwm_trigger_set(_pins[i + 1], enable ? PWM_1_CAMERA_INSTANT_SHOOT : PWM_CAMERA_NEUTRAL);
|
||||
up_pwm_trigger_set(_pins[i + 1], trigger_on_true ? PWM_1_CAMERA_INSTANT_SHOOT : PWM_CAMERA_NEUTRAL);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -18,7 +18,7 @@ public:
|
|||
CameraInterfaceSeagull();
|
||||
virtual ~CameraInterfaceSeagull();
|
||||
|
||||
void trigger(bool enable);
|
||||
void trigger(bool trigger_on_true);
|
||||
|
||||
void send_keep_alive(bool enable);
|
||||
|
||||
|
|
Loading…
Reference in New Issue