mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Camera: add CAMx_OPTION support for start/stop recording when arm/Disarm
This commit is contained in:
parent
0aab2f7974
commit
82b709083c
@ -16,6 +16,14 @@ AP_Camera_Backend::AP_Camera_Backend(AP_Camera &frontend, AP_Camera_Params ¶
|
|||||||
// update - should be called at 50hz
|
// update - should be called at 50hz
|
||||||
void AP_Camera_Backend::update()
|
void AP_Camera_Backend::update()
|
||||||
{
|
{
|
||||||
|
// Check CAMx_OPTIONS and start/stop recording based on arm/disarm
|
||||||
|
if (_params.options.get() & CAMOPTIONS::REC_ARM_DISARM) {
|
||||||
|
if (hal.util->get_soft_armed() != last_is_armed) {
|
||||||
|
last_is_armed = hal.util->get_soft_armed();
|
||||||
|
record_video(last_is_armed);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// try to take picture if pending
|
// try to take picture if pending
|
||||||
if (trigger_pending) {
|
if (trigger_pending) {
|
||||||
take_picture();
|
take_picture();
|
||||||
|
@ -36,6 +36,11 @@ public:
|
|||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
CLASS_NO_COPY(AP_Camera_Backend);
|
CLASS_NO_COPY(AP_Camera_Backend);
|
||||||
|
|
||||||
|
enum CAMOPTIONS {
|
||||||
|
NONE = 0,
|
||||||
|
REC_ARM_DISARM = 1, // Recording start/stop on Arm/Disarm
|
||||||
|
};
|
||||||
|
|
||||||
// init - performs any required initialisation
|
// init - performs any required initialisation
|
||||||
virtual void init() {};
|
virtual void init() {};
|
||||||
|
|
||||||
@ -138,6 +143,7 @@ protected:
|
|||||||
uint32_t last_photo_time_ms; // system time that photo was last taken
|
uint32_t last_photo_time_ms; // system time that photo was last taken
|
||||||
Location last_location; // Location that last picture was taken at (used for trigg_dist calculation)
|
Location last_location; // Location that last picture was taken at (used for trigg_dist calculation)
|
||||||
uint16_t image_index; // number of pictures taken since boot
|
uint16_t image_index; // number of pictures taken since boot
|
||||||
|
bool last_is_armed; // stores last arm/disarm state. true if it was armed lastly
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // AP_CAMERA_ENABLED
|
#endif // AP_CAMERA_ENABLED
|
||||||
|
@ -74,6 +74,13 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = {
|
|||||||
// @User: Standard
|
// @User: Standard
|
||||||
AP_GROUPINFO("_FEEDBAK_POL", 9, AP_Camera_Params, feedback_polarity, 1),
|
AP_GROUPINFO("_FEEDBAK_POL", 9, AP_Camera_Params, feedback_polarity, 1),
|
||||||
|
|
||||||
|
// @Param: _OPTIONS
|
||||||
|
// @DisplayName: Camera options
|
||||||
|
// @Description: Camera options bitmask
|
||||||
|
// @Bitmask: 0:None,1: Recording Starts at arming and stops at disarming
|
||||||
|
// @User: Standard
|
||||||
|
AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -21,6 +21,7 @@ public:
|
|||||||
AP_Float trigg_dist; // distance between trigger points (meters)
|
AP_Float trigg_dist; // distance between trigger points (meters)
|
||||||
AP_Int8 relay_on; // relay value to trigger camera
|
AP_Int8 relay_on; // relay value to trigger camera
|
||||||
AP_Float interval_min; // minimum time (in seconds) between shots required by camera
|
AP_Float interval_min; // minimum time (in seconds) between shots required by camera
|
||||||
|
AP_Int8 options; // whether to start recording when armed and stop when disarmed
|
||||||
|
|
||||||
// pin number for accurate camera feedback messages
|
// pin number for accurate camera feedback messages
|
||||||
AP_Int8 feedback_pin;
|
AP_Int8 feedback_pin;
|
||||||
|
Loading…
Reference in New Issue
Block a user