AP_Camera: removed 3 camera trigger types that do not work

the trigger by wp distance, trigger with throttle off and trigger a
transistor all don't work, and are not structured correctly, plus are
dangerous.

The existing relay support can (correctly!) handle the resistor case
without hard-wiring a pin. The "turn off throttle to trigger" idea is
badly broken, it would crash a copter if it worked. We can make it
work properly on planes if there is demand. As it was it didn't work
anyway. 

The triggger by wp distance method was broken, and had no way to
initiate a trigger anyway
This commit is contained in:
Andrew Tridgell 2013-07-15 09:55:38 +10:00
parent ed20c4cbc8
commit 0f72eae216
2 changed files with 1 additions and 57 deletions

View File

@ -7,7 +7,6 @@
#include <AP_HAL.h> #include <AP_HAL.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
extern int32_t wp_distance; // Note: unfortunately this variable is in meter for ArduPlane and cm for ArduCopter
// ------------------------------ // ------------------------------
#define CAM_DEBUG DISABLED #define CAM_DEBUG DISABLED
@ -16,7 +15,7 @@ const AP_Param::GroupInfo AP_Camera::var_info[] PROGMEM = {
// @Param: TRIGG_TYPE // @Param: TRIGG_TYPE
// @DisplayName: Camera shutter (trigger) type // @DisplayName: Camera shutter (trigger) type
// @Description: how to trigger the camera to take a picture // @Description: how to trigger the camera to take a picture
// @Values: 0:Servo,1:Relay,2:Servo and turn off throttle,3:Servo when 3m from waypoint,4:transistor // @Values: 0:Servo,1:Relay
// @User: Standard // @User: Standard
AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, _trigger_type, AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE), AP_GROUPINFO("TRIGG_TYPE", 0, AP_Camera, _trigger_type, AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE),
@ -72,40 +71,6 @@ AP_Camera::relay_pic()
_trigger_counter = constrain_int16(_trigger_duration*5,0,255); _trigger_counter = constrain_int16(_trigger_duration*5,0,255);
} }
/// pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
void
AP_Camera::throttle_pic()
{
// TODO find a way to do this without using the global parameter g
// g.channel_throttle.radio_out = g.throttle_min;
if (_thr_pic_counter == 10) {
servo_pic(); // triggering method
_thr_pic_counter = 0;
// g.channel_throttle.radio_out = g.throttle_cruise;
}
_thr_pic_counter++;
}
/// distance_pic - triggers picture when within 3m of waypoint
void
AP_Camera::distance_pic()
{
if (wp_distance < AP_CAMERA_WP_DISTANCE) {
servo_pic(); // triggering method
}
}
/// hacked the circuit to run a transistor? use this trigger to send output.
void
AP_Camera::transistor_pic()
{
// TODO: Assign pin spare pin for output
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN,1);
// leave a message that it should be active for two event loop cycles
_trigger_counter = 1;
}
/// single entry point to take pictures /// single entry point to take pictures
void void
AP_Camera::trigger_pic() AP_Camera::trigger_pic()
@ -118,15 +83,6 @@ AP_Camera::trigger_pic()
case AP_CAMERA_TRIGGER_TYPE_RELAY: case AP_CAMERA_TRIGGER_TYPE_RELAY:
relay_pic(); // basic relay activation relay_pic(); // basic relay activation
break; break;
case AP_CAMERA_TRIGGER_TYPE_THROTTLE_OFF_TIME:
throttle_pic(); // pictures blurry? use this trigger. Turns off the throttle until for # of cycles of medium loop then takes the picture and re-enables the throttle.
break;
case AP_CAMERA_TRIGGER_TYPE_WP_DISTANCE:
distance_pic(); // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
break;
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
transistor_pic(); // hacked the circuit to run a transistor? use this trigger to send output.
break;
} }
} }
@ -140,16 +96,11 @@ AP_Camera::trigger_pic_cleanup()
} else { } else {
switch (_trigger_type) { switch (_trigger_type) {
case AP_CAMERA_TRIGGER_TYPE_SERVO: case AP_CAMERA_TRIGGER_TYPE_SERVO:
case AP_CAMERA_TRIGGER_TYPE_THROTTLE_OFF_TIME:
case AP_CAMERA_TRIGGER_TYPE_WP_DISTANCE:
RC_Channel_aux::set_radio(RC_Channel_aux::k_cam_trigger, _servo_off_pwm); RC_Channel_aux::set_radio(RC_Channel_aux::k_cam_trigger, _servo_off_pwm);
break; break;
case AP_CAMERA_TRIGGER_TYPE_RELAY: case AP_CAMERA_TRIGGER_TYPE_RELAY:
_apm_relay->off(); _apm_relay->off();
break; break;
case AP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
hal.gpio->write(AP_CAMERA_TRANSISTOR_PIN, 0);
break;
} }
} }
} }

View File

@ -13,13 +13,6 @@
#define AP_CAMERA_TRIGGER_TYPE_SERVO 0 #define AP_CAMERA_TRIGGER_TYPE_SERVO 0
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1 #define AP_CAMERA_TRIGGER_TYPE_RELAY 1
#define AP_CAMERA_TRIGGER_TYPE_THROTTLE_OFF_TIME 2
#define AP_CAMERA_TRIGGER_TYPE_WP_DISTANCE 3
#define AP_CAMERA_TRIGGER_TYPE_TRANSISTOR 4
#define AP_CAMERA_TRANSISTOR_PIN 83 // PK6 chosen as it not near anything so safer for soldering
#define AP_CAMERA_WP_DISTANCE 3 // trigger camera shutter when within this many meters of target. Unfortunately this variable is in meter for ArduPlane and cm for ArduCopter so it will not work for ArduCopter
#define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO // default is to use servo to trigger camera #define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO // default is to use servo to trigger camera