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
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;
caseAP_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;
caseAP_CAMERA_TRIGGER_TYPE_TRANSISTOR:
transistor_pic();// hacked the circuit to run a transistor? use this trigger to send output.
#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