6 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4     7 #include <drivers/drv_input_capture.h>     8 #include <drivers/drv_pwm_output.h>    16 #define CAM_DEBUG DISABLED   183     __mavlink_digicam_control_t packet;
   184     mavlink_msg_digicam_control_decode(msg, &packet);
   186     control(packet.session, packet.zoom_pos, packet.zoom_step, packet.focus_lock, packet.shot, packet.command_id);
   189 void AP_Camera::configure(
float shooting_mode, 
float shutter_speed, 
float aperture, 
float ISO, 
float exposure_type, 
float cmd_id, 
float engine_cutoff_time)
   194     mavlink_message_t msg;
   195     mavlink_command_long_t mav_cmd_long = {};
   198     mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONFIGURE;
   199     mav_cmd_long.param1 = shooting_mode;
   200     mav_cmd_long.param2 = shutter_speed;
   201     mav_cmd_long.param3 = aperture;
   202     mav_cmd_long.param4 = ISO;
   203     mav_cmd_long.param5 = exposure_type;
   204     mav_cmd_long.param6 = cmd_id;
   205     mav_cmd_long.param7 = engine_cutoff_time;
   208     mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
   214 void AP_Camera::control(
float session, 
float zoom_pos, 
float zoom_step, 
float focus_lock, 
float shooting_cmd, 
float cmd_id)
   221     mavlink_message_t msg;
   222     mavlink_command_long_t mav_cmd_long = {};
   225     mav_cmd_long.command = MAV_CMD_DO_DIGICAM_CONTROL;
   226     mav_cmd_long.param1 = session;
   227     mav_cmd_long.param2 = zoom_pos;
   228     mav_cmd_long.param3 = zoom_step;
   229     mav_cmd_long.param4 = focus_lock;
   230     mav_cmd_long.param5 = shooting_cmd;
   231     mav_cmd_long.param6 = cmd_id;
   234     mavlink_msg_command_long_encode(0, 0, &msg, &mav_cmd_long);
   245     float altitude, altitude_rel;
   254     mavlink_msg_camera_feedback_send(
   259         altitude*1e-2, altitude_rel*1e-2,
   324     uint8_t pin_state = hal.
gpio->
read(dpin);
   326     if (pin_state == trigger_polarity &&
   345 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4   350                                  hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
   367 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4   372         int fd = 
open(
"/dev/px4fmu", 0);
   374             if (ioctl(fd, PWM_SERVO_SET_MODE, PWM_SERVO_MODE_3PWM1CAP) != 0) {
   375                 gcs().
send_text(MAV_SEVERITY_WARNING, 
"Camera: unable to setup 3PWM1CAP");
   380                 gcs().
send_text(MAV_SEVERITY_WARNING, 
"Camera: unable to setup timer capture");
   386             gcs().
send_text(MAV_SEVERITY_WARNING, 
"Camera: setup fast trigger capture");
   390 #endif // CONFIG_HAL_BOARD   425     mavlink_command_long_t cmd_msg;
   426     memset(&cmd_msg, 0, 
sizeof(cmd_msg));
   427     cmd_msg.command = MAV_CMD_DO_DIGICAM_CONTROL;
   430     mavlink_message_t msg;
   431     mavlink_msg_command_long_encode(0, 0, &msg, &cmd_msg);
 static void send_to_components(const mavlink_message_t *msg)
 
virtual int8_t analogPinToDigitalPin(uint8_t pin)=0
 
void Log_Write_Trigger(const AP_AHRS &ahrs, const Location ¤t_loc)
 
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
 
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags. 
 
void control_msg(const mavlink_message_t *msg)
decode deprecated MavLink message that controls camera. 
 
static volatile bool _camera_triggered
 
bool should_log(uint32_t mask) const
 
const struct Location & get_home(void) const
 
void feedback_pin_timer()
 
#define AP_GROUPINFO(name, idx, clazz, element, def)
 
float get_distance(const struct Location &loc1, const struct Location &loc2)
 
#define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE
 
virtual void write(uint8_t pin, uint8_t value)=0
 
int32_t lat
param 3 - Latitude * 10**7 
 
AP_Int8 _feedback_polarity
 
struct Location _last_location
 
void send_message(enum ap_message id)
 
AP_Int8 _trigger_duration
 
uint16_t _feedback_events
 
#define AP_CAMERA_SERVO_OFF_PWM
 
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M 
 
RC_Channel manager, with EEPROM-backed storage of constants. 
 
static const struct AP_Param::GroupInfo var_info[]
 
void Log_Write_Camera(const AP_AHRS &ahrs, const Location ¤t_loc)
 
bool is_zero(const T fVal1)
 
static void set_output_pwm(SRV_Channel::Aux_servo_function_t function, uint16_t value)
 
int close(int fileno)
POSIX Close a file with fileno handel. 
 
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time)
 
static DataFlash_Class * instance(void)
 
static void capture_callback(void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
 
virtual void pinMode(uint8_t pin, uint8_t output)=0
 
uint32_t _last_photo_time
 
bool check_trigger_pin(void)
 
void send_text(MAV_SEVERITY severity, const char *fmt,...)
 
void send_feedback(mavlink_channel_t chan)
 
bool using_feedback_pin(void) const
 
void servo_pic()
Servo operated camera. 
 
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude) 
 
void trigger_pic_cleanup()
 
void relay_pic()
basic relay activation 
 
#define AP_CAMERA_TRIGGER_TYPE_RELAY
 
virtual void register_timer_process(AP_HAL::MemberProc)=0
 
virtual uint8_t read(uint8_t pin)=0
 
int32_t lng
param 4 - Longitude * 10**7 
 
#define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN
 
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
 
AP_HAL::AnalogSource * chan
 
#define AP_CAMERA_TRIGGER_DEFAULT_DURATION
 
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
 
#define AP_CAMERA_TRIGGER_TYPE_SERVO
 
Receiving valid messages and 3D lock. 
 
#define AP_CAMERA_SERVO_ON_PWM
 
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id)
 
const struct Location & current_loc
 
Photo or video camera manager, with EEPROM-backed storage of constants. 
 
AP_HAL::Scheduler * scheduler
 
void setup_feedback_callback(void)