keep_cam_trigg_active_cycles=2;// leave a message that it should be active for two event loop cycles
}
}
void
AP_Camera::relay_pic()// basic relay activation
{
relay_on();
keep_cam_trigg_active_cycles=2;// leave a message that it should be active for two event loop cycles
}
void
AP_Camera::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.
{
// TODO find a way to do this without using the global parameter g
AP_Camera::distance_pic()// pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
{
// TODO find a way to do this without using the global parameter g
AP_Camera::NPN_pic()// hacked the circuit to run a transistor? use this trigger to send output.
{
// TODO: Assign pin spare pin for output
digitalWrite(camtrig,HIGH);
keep_cam_trigg_active_cycles=1;// leave a message that it should be active for two event loop cycles
}
// single entry point to take pictures
void
AP_Camera::trigger_pic()
{
switch(trigger_type)
{
case0:
servo_pic();// Servo operated camera
break;
case1:
relay_pic();// basic relay activation
break;
case2:
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;
case3:
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;
case4:
NPN_pic();// hacked the circuit to run a transistor? use this trigger to send output.
break;
}
}
// de-activate the trigger after some delay, but without using a delay() function