13 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 14 #include <drivers/drv_hrt.h> 17 #define AP_CAMERA_TRIGGER_TYPE_SERVO 0 18 #define AP_CAMERA_TRIGGER_TYPE_RELAY 1 20 #define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_SERVO // default is to use servo to trigger camera 22 #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) 24 #define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated 25 #define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated 27 #define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1 // default is to not use camera feedback pin 55 void configure(
float shooting_mode,
float shutter_speed,
float aperture,
float ISO,
float exposure_type,
float cmd_id,
float engine_cutoff_time);
57 void control(
float session,
float zoom_pos,
float zoom_step,
float focus_lock,
float shooting_cmd,
float cmd_id);
90 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 92 hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow);
void control_msg(const mavlink_message_t *msg)
decode deprecated MavLink message that controls camera.
Interface definition for the various Ground Control System.
static volatile bool _camera_triggered
void feedback_pin_timer()
AP_Camera & operator=(const AP_Camera &)=delete
AP_Int8 _feedback_polarity
struct Location _last_location
A system for managing and storing variables that are of general interest to the system.
AP_Int8 _trigger_duration
uint16_t _feedback_events
static const struct AP_Param::GroupInfo var_info[]
AP_Camera(AP_Relay *obj_relay, uint32_t _log_camera_bit, const struct Location &_loc, const AP_AHRS &_ahrs)
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
Handles the MAVLINK command mission stack. Reads and writes mission to storage.
static void capture_callback(void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
uint32_t _last_photo_time
bool check_trigger_pin(void)
void send_feedback(mavlink_channel_t chan)
bool using_feedback_pin(void) const
void servo_pic()
Servo operated camera.
void trigger_pic_cleanup()
void relay_pic()
basic relay activation
Common definitions and utility routines for the ArduPilot libraries.
Class to manage the ArduPilot relay.
void set_trigger_distance(uint32_t distance_m)
AP_HAL::AnalogSource * chan
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
const struct Location & current_loc
void set_is_auto_mode(bool enable)
void setup_feedback_callback(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)