mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 17:38:32 -04:00
APMrover2: Added precise camera trigger logging
included update_trigger function added camera trigger precise time mark detect camera feedback pin status added support for TRIGGER MSG corrected according to defines.h
This commit is contained in:
parent
90bf13279b
commit
f731a0dc53
@ -68,6 +68,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||||||
SCHED_TASK(update_events, 50, 1000),
|
SCHED_TASK(update_events, 50, 1000),
|
||||||
SCHED_TASK(check_usb_mux, 3, 1000),
|
SCHED_TASK(check_usb_mux, 3, 1000),
|
||||||
SCHED_TASK(mount_update, 50, 600),
|
SCHED_TASK(mount_update, 50, 600),
|
||||||
|
SCHED_TASK(update_trigger, 1, 600),
|
||||||
SCHED_TASK(gcs_failsafe_check, 10, 600),
|
SCHED_TASK(gcs_failsafe_check, 10, 600),
|
||||||
SCHED_TASK(compass_accumulate, 50, 900),
|
SCHED_TASK(compass_accumulate, 50, 900),
|
||||||
SCHED_TASK(update_notify, 50, 300),
|
SCHED_TASK(update_notify, 50, 300),
|
||||||
@ -178,8 +179,22 @@ void Rover::mount_update(void)
|
|||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
camera_mount.update();
|
camera_mount.update();
|
||||||
#endif
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
update camera trigger - 50Hz
|
||||||
|
*/
|
||||||
|
void Rover::update_trigger(void)
|
||||||
|
{
|
||||||
#if CAMERA == ENABLED
|
#if CAMERA == ENABLED
|
||||||
camera.trigger_pic_cleanup();
|
camera.trigger_pic_cleanup();
|
||||||
|
if(camera._camera_triggered == 0 && camera._feedback_pin != -1 && check_digital_pin(camera._feedback_pin) == 0){
|
||||||
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||||
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||||
|
}
|
||||||
|
camera._camera_triggered = 1;
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -48,6 +48,7 @@ bool Rover::print_log_menu(void)
|
|||||||
PLOG(COMPASS);
|
PLOG(COMPASS);
|
||||||
PLOG(CAMERA);
|
PLOG(CAMERA);
|
||||||
PLOG(STEERING);
|
PLOG(STEERING);
|
||||||
|
PLOG(TRIGGER);
|
||||||
#undef PLOG
|
#undef PLOG
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -127,6 +128,7 @@ int8_t Rover::select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
TARG(COMPASS);
|
TARG(COMPASS);
|
||||||
TARG(CAMERA);
|
TARG(CAMERA);
|
||||||
TARG(STEERING);
|
TARG(STEERING);
|
||||||
|
TARG(TRIGGER);
|
||||||
#undef TARG
|
#undef TARG
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -476,4 +478,3 @@ void Rover::start_logging() {}
|
|||||||
void Rover::Log_Write_RC(void) {}
|
void Rover::Log_Write_RC(void) {}
|
||||||
|
|
||||||
#endif // LOGGING_ENABLED
|
#endif // LOGGING_ENABLED
|
||||||
|
|
||||||
|
@ -380,6 +380,7 @@ private:
|
|||||||
// private member functions
|
// private member functions
|
||||||
void ahrs_update();
|
void ahrs_update();
|
||||||
void mount_update(void);
|
void mount_update(void);
|
||||||
|
void update_trigger(void);
|
||||||
void update_alt();
|
void update_alt();
|
||||||
void gcs_failsafe_check(void);
|
void gcs_failsafe_check(void);
|
||||||
void compass_accumulate(void);
|
void compass_accumulate(void);
|
||||||
|
@ -370,8 +370,16 @@ void Rover::do_take_picture()
|
|||||||
// log_picture - log picture taken and send feedback to GCS
|
// log_picture - log picture taken and send feedback to GCS
|
||||||
void Rover::log_picture()
|
void Rover::log_picture()
|
||||||
{
|
{
|
||||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
if (camera._feedback_pin == -1 ){
|
||||||
if (should_log(MASK_LOG_CAMERA)) {
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
camera._camera_triggered = 0;
|
||||||
|
if (should_log(MASK_LOG_TRIGGER)) {
|
||||||
|
DataFlash.Log_Write_Trigger(ahrs, gps, current_loc);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -92,6 +92,8 @@ enum mode {
|
|||||||
#define MASK_LOG_ARM_DISARM (1<<15)
|
#define MASK_LOG_ARM_DISARM (1<<15)
|
||||||
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
|
#define MASK_LOG_WHEN_DISARMED (1UL<<16)
|
||||||
#define MASK_LOG_IMU_RAW (1UL<<19)
|
#define MASK_LOG_IMU_RAW (1UL<<19)
|
||||||
|
#define MASK_LOG_TRIGGER (1UL<<20)
|
||||||
|
|
||||||
|
|
||||||
// Waypoint Modes
|
// Waypoint Modes
|
||||||
// ----------------
|
// ----------------
|
||||||
|
Loading…
Reference in New Issue
Block a user