mirror of https://github.com/ArduPilot/ardupilot
APMrover2: update for changed AP_Camera API
This commit is contained in:
parent
061ee5e4fd
commit
eed575886c
|
@ -68,7 +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(update_trigger, 50, 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),
|
||||||
|
@ -188,12 +188,11 @@ 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){
|
if (camera.check_trigger_pin()) {
|
||||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||||
if (should_log(MASK_LOG_CAMERA)) {
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||||
}
|
}
|
||||||
camera._camera_triggered = 1;
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
|
@ -48,7 +48,6 @@ bool Rover::print_log_menu(void)
|
||||||
PLOG(COMPASS);
|
PLOG(COMPASS);
|
||||||
PLOG(CAMERA);
|
PLOG(CAMERA);
|
||||||
PLOG(STEERING);
|
PLOG(STEERING);
|
||||||
PLOG(TRIGGER);
|
|
||||||
#undef PLOG
|
#undef PLOG
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -128,7 +127,6 @@ 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
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -370,16 +370,14 @@ 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()
|
||||||
{
|
{
|
||||||
if (camera._feedback_pin == -1 ){
|
if (!camera.using_feedback_pin()) {
|
||||||
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
gcs_send_message(MSG_CAMERA_FEEDBACK);
|
||||||
if (should_log(MASK_LOG_CAMERA)) {
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
DataFlash.Log_Write_Camera(ahrs, gps, current_loc);
|
||||||
}
|
}
|
||||||
}
|
} else {
|
||||||
else {
|
if (should_log(MASK_LOG_CAMERA)) {
|
||||||
camera._camera_triggered = 0;
|
DataFlash.Log_Write_Trigger(ahrs, gps, current_loc);
|
||||||
if (should_log(MASK_LOG_TRIGGER)) {
|
}
|
||||||
DataFlash.Log_Write_Trigger(ahrs, gps, current_loc);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
|
@ -92,7 +92,6 @@ 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