mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
AP_Camera: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
6e27488bfd
commit
4b30963d1d
@ -140,7 +140,9 @@ bool AP_Camera_Backend::take_picture()
|
|||||||
image_index++;
|
image_index++;
|
||||||
last_picture_time_ms = now_ms;
|
last_picture_time_ms = now_ms;
|
||||||
IGNORE_RETURN(AP::ahrs().get_location(last_location));
|
IGNORE_RETURN(AP::ahrs().get_location(last_location));
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
log_picture();
|
log_picture();
|
||||||
|
#endif
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -358,16 +360,20 @@ void AP_Camera_Backend::feedback_pin_timer()
|
|||||||
void AP_Camera_Backend::check_feedback()
|
void AP_Camera_Backend::check_feedback()
|
||||||
{
|
{
|
||||||
if (feedback_trigger_logged_count != feedback_trigger_count) {
|
if (feedback_trigger_logged_count != feedback_trigger_count) {
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
const uint32_t timestamp32 = feedback_trigger_timestamp_us;
|
const uint32_t timestamp32 = feedback_trigger_timestamp_us;
|
||||||
|
#endif
|
||||||
feedback_trigger_logged_count = feedback_trigger_count;
|
feedback_trigger_logged_count = feedback_trigger_count;
|
||||||
|
|
||||||
// we should consider doing this inside the ISR and pin_timer
|
// we should consider doing this inside the ISR and pin_timer
|
||||||
prep_mavlink_msg_camera_feedback(feedback_trigger_timestamp_us);
|
prep_mavlink_msg_camera_feedback(feedback_trigger_timestamp_us);
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log camera message
|
// log camera message
|
||||||
uint32_t tdiff = AP_HAL::micros() - timestamp32;
|
uint32_t tdiff = AP_HAL::micros() - timestamp32;
|
||||||
uint64_t timestamp = AP_HAL::micros64();
|
uint64_t timestamp = AP_HAL::micros64();
|
||||||
Write_Camera(timestamp - tdiff);
|
Write_Camera(timestamp - tdiff);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -386,6 +392,7 @@ void AP_Camera_Backend::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us)
|
|||||||
GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK);
|
GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// log picture
|
// log picture
|
||||||
void AP_Camera_Backend::log_picture()
|
void AP_Camera_Backend::log_picture()
|
||||||
{
|
{
|
||||||
@ -404,5 +411,6 @@ void AP_Camera_Backend::log_picture()
|
|||||||
Write_Trigger();
|
Write_Trigger();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // AP_CAMERA_ENABLED
|
#endif // AP_CAMERA_ENABLED
|
||||||
|
@ -1,7 +1,8 @@
|
|||||||
#include "AP_Camera_Backend.h"
|
#include "AP_Camera_Backend.h"
|
||||||
#include <AP_Mount/AP_Mount.h>
|
#include <AP_Mount/AP_Mount.h>
|
||||||
|
#include <AP_Logger/AP_Logger_config.h>
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED
|
||||||
|
|
||||||
#include <AP_Logger/AP_Logger.h>
|
#include <AP_Logger/AP_Logger.h>
|
||||||
#include <AP_GPS/AP_GPS.h>
|
#include <AP_GPS/AP_GPS.h>
|
||||||
@ -85,4 +86,4 @@ void AP_Camera_Backend::Write_Trigger()
|
|||||||
Write_CameraInfo(LOG_TRIGGER_MSG, 0);
|
Write_CameraInfo(LOG_TRIGGER_MSG, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif // AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user