AP_Mount: allow compilation with HAL_LOGGING_ENABLED false

This commit is contained in:
Peter Barker 2023-07-14 10:58:07 +10:00 committed by Andrew Tridgell
parent bccfd98d0e
commit a6db3bd069
5 changed files with 18 additions and 3 deletions

View File

@ -712,6 +712,7 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_
backend->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg);
}
#if HAL_LOGGING_ENABLED
// write mount log packet for all backends
void AP_Mount::write_log()
{
@ -731,6 +732,7 @@ void AP_Mount::write_log(uint8_t instance, uint64_t timestamp_us)
}
backend->write_log(timestamp_us);
}
#endif
// point at system ID sysid
void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid)

View File

@ -409,6 +409,7 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli
return true;
}
#if HAL_LOGGING_ENABLED
// write mount log packet
void AP_Mount_Backend::write_log(uint64_t timestamp_us)
{
@ -456,6 +457,7 @@ void AP_Mount_Backend::write_log(uint64_t timestamp_us)
};
AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt));
}
#endif
#if AP_MOUNT_POI_TO_LATLONALT_ENABLED
// get poi information. Returns true on success and fills in gimbal attitude, location and poi location

View File

@ -125,19 +125,26 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav
_gimbal.update_target(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()});
_gimbal.receive_feedback(chan,msg);
#if HAL_LOGGING_ENABLED
AP_Logger *logger = AP_Logger::get_singleton();
if (logger == nullptr) {
return;
}
if(!_params_saved && logger->logging_started()) {
#endif
if(!_params_saved
#if HAL_LOGGING_ENABLED
&& logger->logging_started()
#endif
) {
_gimbal.fetch_params(); //last parameter save might not be stored in logger so retry
_params_saved = true;
}
#if HAL_LOGGING_ENABLED
if (_gimbal.get_log_dt() > 1.0f/25.0f) {
_gimbal.write_logs();
}
#endif
}
void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t &msg)

View File

@ -400,6 +400,7 @@ void SoloGimbal::update_target(const Vector3f &newTarget)
_att_target_euler_rad.x = constrain_float(_att_target_euler_rad.x,radians(-30),radians(30));
}
#if HAL_LOGGING_ENABLED
void SoloGimbal::write_logs()
{
AP_Logger &logger = AP::logger();
@ -481,6 +482,7 @@ void SoloGimbal::write_logs()
_log_del_ang.zero();
_log_del_vel.zero();
}
#endif
bool SoloGimbal::joints_near_limits() const
{

View File

@ -187,10 +187,12 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t &msg)
mavlink_param_value_t packet;
mavlink_msg_param_value_decode(&msg, &packet);
#if HAL_LOGGING_ENABLED
AP_Logger *logger = AP_Logger::get_singleton();
if (logger != nullptr) {
logger->Write_Parameter(packet.param_id, packet.param_value);
}
#endif
for(uint8_t i=0; i<MAVLINK_GIMBAL_NUM_TRACKED_PARAMS; i++) {
if (!strcmp(packet.param_id, get_param_name((gmb_param_t)i))) {
@ -294,4 +296,4 @@ bool SoloGimbal_Parameters::flashing()
return _flashing_step != GMB_PARAM_NOT_FLASHING;
}
#endif // HAL_SOLO_GIMBAL_ENABLED
#endif // HAL_SOLO_GIMBAL_ENABLED