#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_DURATION 10 // default duration servo or relay is held open in 10ths of a second (i.e. 10 = 1 second)
#define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated
#define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated
voidthrottle_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.
voiddistance_pic();// pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
voidtransistor_pic();// hacked the circuit to run a transistor? use this trigger to send output.