2012-06-13 16:00:20 -03:00
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
/// @file AP_Camera.h
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
2012-06-17 17:53:54 -03:00
/// @author Amilcar Lucas
2012-06-13 16:00:20 -03:00
# ifndef AP_CAMERA_H
# define AP_CAMERA_H
# include <AP_Common.h>
# include <GCS_MAVLink.h>
/// @class Camera
/// @brief Object managing a Photo or video camera
2012-08-17 03:09:29 -03:00
class AP_Camera {
2012-06-13 16:00:20 -03:00
public :
2012-08-17 03:09:29 -03:00
/// Constructor
///
AP_Camera ( ) :
picture_time ( 0 ) , // waypoint trigger variable
wp_distance_min ( 10 ) ,
keep_cam_trigg_active_cycles ( 0 ) ,
thr_pic ( 0 ) , // timer variable for throttle_pic
camtrig ( 83 ) // PK6 chosen as it not near anything so safer for soldering
{
}
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
// single entry point to take pictures
void trigger_pic ( ) ;
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
// de-activate the trigger after some delay, but without using a delay() function
void trigger_pic_cleanup ( ) ;
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
// MAVLink methods
void configure_msg ( mavlink_message_t * msg ) ;
void control_msg ( mavlink_message_t * msg ) ;
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
int16_t picture_time ; ///< waypoint trigger variable
int32_t wp_distance_min ; ///< take picture if distance to WP is smaller than this
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
static const struct AP_Param : : GroupInfo var_info [ ] ;
2012-06-13 16:00:20 -03:00
private :
2012-08-17 03:09:29 -03:00
uint8_t keep_cam_trigg_active_cycles ; ///< event loop cycles to keep trigger active
int16_t thr_pic ; ///< timer variable for throttle_pic
int16_t camtrig ; ///< PK6 chosen as it not near anything so safer for soldering
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
AP_Int8 trigger_type ; ///< 0=Servo, 1=relay, 2=throttle_off time, 3=throttle_off waypoint, 4=transistor
2012-06-13 16:00:20 -03:00
2012-08-17 03:09:29 -03:00
void servo_pic ( ) ; // Servo operated camera
void relay_pic ( ) ; // basic relay activation
void 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.
void distance_pic ( ) ; // pictures blurry? use this trigger. Turns off the throttle until closer to waypoint then takes the picture and re-enables the throttle.
void NPN_pic ( ) ; // hacked the circuit to run a transistor? use this trigger to send output.
2012-06-13 16:00:20 -03:00
} ;
# endif /* AP_CAMERA_H */