|
|
|
/// @file AP_Camera.h
|
|
|
|
/// @brief Photo or video camera manager, with EEPROM-backed storage of constants.
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
|
|
|
|
#define AP_CAMERA_TRIGGER_TYPE_SERVO 0
|
|
|
|
#define AP_CAMERA_TRIGGER_TYPE_RELAY 1
|
|
|
|
#define AP_CAMERA_TRIGGER_TYPE_UAVCAN 2
|
|
|
|
|
|
|
|
#define AP_CAMERA_TRIGGER_DEFAULT_TRIGGER_TYPE AP_CAMERA_TRIGGER_TYPE_RELAY // default is to use servo to trigger camera
|
|
|
|
|
|
|
|
#define AP_CAMERA_TRIGGER_DEFAULT_DURATION 3 // default duration servo or relay is held open in 10ths of a second (i.e. 10 = 1 second)
|
|
|
|
|
|
|
|
#define AP_CAMERA_SERVO_ON_PWM 1300 // default PWM value to move servo to when shutter is activated
|
|
|
|
#define AP_CAMERA_SERVO_OFF_PWM 1100 // default PWM value to move servo to when shutter is deactivated
|
|
|
|
|
|
|
|
#define AP_CAMERA_FEEDBACK_DEFAULT_FEEDBACK_PIN -1 // default is to not use camera feedback pin
|
|
|
|
|
|
|
|
/// @class Camera
|
|
|
|
/// @brief Object managing a Photo or video camera
|
|
|
|
class AP_Camera {
|
|
|
|
|
|
|
|
public:
|
|
|
|
AP_Camera(uint32_t _log_camera_bit, const struct Location &_loc)
|
|
|
|
: log_camera_bit(_log_camera_bit)
|
|
|
|
, current_loc(_loc)
|
|
|
|
{
|
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
_singleton = this;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
|
|
|
AP_Camera(const AP_Camera &other) = delete;
|
|
|
|
AP_Camera &operator=(const AP_Camera&) = delete;
|
|
|
|
|
|
|
|
// get singleton instance
|
|
|
|
static AP_Camera *get_singleton()
|
|
|
|
{
|
|
|
|
return _singleton;
|
|
|
|
}
|
|
|
|
|
|
|
|
// MAVLink methods
|
|
|
|
void control_msg(const mavlink_message_t &msg);
|
|
|
|
void send_feedback(mavlink_channel_t chan);
|
|
|
|
|
|
|
|
// Command processing
|
|
|
|
void configure(float shooting_mode, float shutter_speed, float aperture, float ISO, float exposure_type, float cmd_id, float engine_cutoff_time);
|
|
|
|
// handle camera control
|
|
|
|
void control(float session, float zoom_pos, float zoom_step, float focus_lock, float shooting_cmd, float cmd_id);
|
|
|
|
|
|
|
|
// set camera trigger distance in a mission
|
|
|
|
void set_trigger_distance(uint32_t distance_m)
|
|
|
|
{
|
|
|
|
_trigg_dist.set(distance_m);
|
|
|
|
}
|
|
|
|
|
|
|
|
void take_picture();
|
|
|
|
void uavcan_pic();
|
|
|
|
uint8_t send_msg_step;
|
|
|
|
// Update - to be called periodically @at least 10Hz
|
|
|
|
void update();
|
|
|
|
|
|
|
|
// update camera trigger - 50Hz
|
|
|
|
void update_trigger();
|
|
|
|
const char* get_camera_sn(void);
|
|
|
|
const char* get_camrea_ver(void);
|
|
|
|
void set_camera_sn(char * sn);
|
|
|
|
void set_camera_ver(char * ver);
|
|
|
|
void request_camera_sn(void);
|
|
|
|
void update_zr_camera_status();
|
|
|
|
void send_uavcan_camera_zr_control(const mavlink_camera_zr_control_t &packet);
|
|
|
|
void notice_send_camera_status_to_gcs(void);
|
|
|
|
void update_zr_camera_version(void);
|
|
|
|
void send_camera_zr_status(mavlink_channel_t chan);
|
|
|
|
void create_new_folder(uint8_t type);
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
void set_image_index(uint16_t photo_index);
|
|
|
|
uint16_t get_image_index();
|
|
|
|
// set if vehicle is in AUTO mode
|
|
|
|
void set_is_auto_mode(bool enable)
|
|
|
|
{
|
|
|
|
_is_in_auto_mode = enable;
|
|
|
|
}
|
|
|
|
|
|
|
|
enum camera_types {
|
|
|
|
CAMERA_TYPE_STD,
|
|
|
|
CAMERA_TYPE_BMMCC
|
|
|
|
};
|
|
|
|
|
|
|
|
void get_last_trigger_pos(int32_t &lat,int32_t &lng){ lat=last_pos_lat;lng=last_pos_lng; } // @Brown,for get camera pos
|
|
|
|
|
|
|
|
// modivy by @Brown
|
|
|
|
uint16_t number_of_log(void) const { return _image_index_log; }
|
|
|
|
uint16_t number_of_index(void) const { return _image_index; }
|
|
|
|
|
|
|
|
uint16_t _image_index_log; // number of pictures taken to log @Brown
|
|
|
|
uint8_t cameras_take_enable_new;
|
|
|
|
uint8_t cameras_take_enable; //相机是否执行拍照 0有效
|
|
|
|
struct Camera_State
|
|
|
|
{
|
|
|
|
float temperature;
|
|
|
|
uint16_t num[5];
|
|
|
|
// uint16_t num2;
|
|
|
|
// uint16_t num3;
|
|
|
|
// uint16_t num4;
|
|
|
|
// uint16_t num5;
|
|
|
|
uint16_t trigger_num;
|
|
|
|
uint8_t instance; // the instance number of this Camera
|
|
|
|
uint8_t id;
|
|
|
|
uint8_t mode;
|
|
|
|
uint8_t shutter_speed;
|
|
|
|
uint8_t err_code;
|
|
|
|
uint8_t connect_state;
|
|
|
|
uint8_t uavcan_node_id;
|
|
|
|
uint8_t feedback_code;
|
|
|
|
uint8_t usb_enable;
|
|
|
|
};
|
|
|
|
struct Camera_Can_Msg
|
|
|
|
{
|
|
|
|
int32_t lat; // @Brown,for get camera pos
|
|
|
|
int32_t lng;
|
|
|
|
int32_t alt;
|
|
|
|
float roll;
|
|
|
|
float pitch;
|
|
|
|
float yaw;
|
|
|
|
uint8_t mode;
|
|
|
|
};
|
|
|
|
struct Camera_Can_Msg camera_can_msg;
|
|
|
|
struct Camera_State &get_camera_state(){
|
|
|
|
return camera_state;
|
|
|
|
}
|
|
|
|
private:
|
|
|
|
|
|
|
|
static AP_Camera *_singleton;
|
|
|
|
struct Camera_State camera_state;
|
|
|
|
AP_Int8 _trigger_type; // 0:Servo,1:Relay
|
|
|
|
AP_Int8 _trigger_duration; // duration in 10ths of a second that the camera shutter is held open
|
|
|
|
AP_Int8 _relay_on; // relay value to trigger camera
|
|
|
|
AP_Int16 _servo_on_pwm; // PWM value to move servo to when shutter is activated
|
|
|
|
AP_Int16 _servo_off_pwm; // PWM value to move servo to when shutter is deactivated
|
|
|
|
uint8_t _trigger_counter; // count of number of cycles shutter has been held open
|
|
|
|
uint8_t _trigger_counter_cam_function; // count of number of cycles alternative camera function has been held open
|
|
|
|
AP_Int8 _auto_mode_only; // if 1: trigger by distance only if in AUTO mode.
|
|
|
|
AP_Int8 _type; // Set the type of camera in use, will open additional parameters if set
|
|
|
|
bool _is_in_auto_mode; // true if in AUTO mode
|
|
|
|
|
|
|
|
void servo_pic(); // Servo operated camera
|
|
|
|
void relay_pic(); // basic relay activation
|
|
|
|
void feedback_pin_timer();
|
|
|
|
void feedback_pin_isr(uint8_t, bool, uint32_t);
|
|
|
|
void setup_feedback_callback(void);
|
|
|
|
|
|
|
|
AP_Float _trigg_dist; // distance between trigger points (meters)
|
|
|
|
AP_Int16 _min_interval; // Minimum time between shots required by camera
|
|
|
|
AP_Int16 _max_roll; // Maximum acceptable roll angle when trigging camera
|
|
|
|
uint32_t _last_photo_time; // last time a photo was taken
|
|
|
|
struct Location _last_location;
|
|
|
|
uint16_t _image_index; // number of pictures taken since boot
|
|
|
|
|
|
|
|
// pin number for accurate camera feedback messages
|
|
|
|
AP_Int8 _feedback_pin;
|
|
|
|
AP_Int8 _feedback_polarity;
|
|
|
|
|
|
|
|
uint32_t _camera_trigger_count;
|
|
|
|
uint32_t _camera_trigger_logged;
|
|
|
|
uint32_t _feedback_timestamp_us;
|
|
|
|
bool _timer_installed;
|
|
|
|
bool _isr_installed;
|
|
|
|
uint8_t _last_pin_state;
|
|
|
|
|
|
|
|
void log_picture();
|
|
|
|
|
|
|
|
uint32_t log_camera_bit;
|
|
|
|
const struct Location ¤t_loc;
|
|
|
|
|
|
|
|
// entry point to trip local shutter (e.g. by relay or servo)
|
|
|
|
void trigger_pic();
|
|
|
|
|
|
|
|
// de-activate the trigger after some delay, but without using a delay() function
|
|
|
|
// should be called at 50hz from main program
|
|
|
|
void trigger_pic_cleanup();
|
|
|
|
|
|
|
|
// return true if we are using a feedback pin
|
|
|
|
bool using_feedback_pin(void) const
|
|
|
|
{
|
|
|
|
return _feedback_pin > 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
int32_t last_pos_lat; // @Brown,for get camera pos
|
|
|
|
int32_t last_pos_lng;
|
|
|
|
|
|
|
|
char sn[15]; //sn 10 byte str 11byte give 15byte for tomorrow used
|
|
|
|
char sver[12]; //software version
|
|
|
|
|
|
|
|
void send_can_msg(void);
|
|
|
|
};
|
|
|
|
namespace AP {
|
|
|
|
AP_Camera *camera();
|
|
|
|
};
|