int32_twp_distance_min;///< take picture if distance to WP is smaller than this
staticconststructAP_Param::GroupInfovar_info[];
staticconststructAP_Param::GroupInfovar_info[];
private:
uint8_tkeep_cam_trigg_active_cycles;///< event loop cycles to keep trigger active
int16_tthr_pic;///< timer variable for throttle_pic
int16_tcamtrig;///< PK6 chosen as it not near anything so safer for soldering
uint8_tkeep_cam_trigg_active_cycles;///< event loop cycles to keep trigger active
int16_tthr_pic;///< timer variable for throttle_pic
int16_tcamtrig;///< PK6 chosen as it not near anything so safer for soldering
AP_Int8trigger_type;///< 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint, 4=transistor
AP_Int8trigger_type;///< 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint, 4=transistor
voidservo_pic();// Servo operated camera
voidrelay_pic();// basic relay activation
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.
voidNPN_pic();// hacked the circuit to run a transistor? use this trigger to send output.
voidservo_pic();// Servo operated camera
voidrelay_pic();// basic relay activation
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.
voidNPN_pic();// hacked the circuit to run a transistor? use this trigger to send output.