mirror of https://github.com/ArduPilot/ardupilot
Rover: correct compilation when HAL_LOGGING_ENABLED is false
This commit is contained in:
parent
b94fc26c5f
commit
8bdd0294b8
|
@ -106,7 +106,9 @@ void AP_Arming_Rover::update_soft_armed()
|
|||
{
|
||||
hal.util->set_soft_armed(is_armed() &&
|
||||
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -1065,7 +1065,11 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess
|
|||
|
||||
void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
||||
#else
|
||||
handle_radio_status(msg, false);
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
|
||||
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
||||
// Write an attitude packet
|
||||
void Rover::Log_Write_Attitude()
|
||||
|
|
|
@ -316,9 +316,11 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
|
||||
GOBJECT(arming, "ARMING_", AP_Arming),
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||
GOBJECT(logger, "LOG", AP_Logger),
|
||||
#endif
|
||||
|
||||
// @Group: BATT
|
||||
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
||||
|
|
|
@ -89,8 +89,10 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100, 30),
|
||||
SCHED_TASK(update_wheel_encoder, 50, 200, 36),
|
||||
SCHED_TASK(update_compass, 10, 200, 39),
|
||||
#if HAL_LOGGING_ENABLED
|
||||
SCHED_TASK(update_logging1, 10, 200, 45),
|
||||
SCHED_TASK(update_logging2, 10, 200, 48),
|
||||
#endif
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500, 51),
|
||||
SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000, 54),
|
||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200, 57),
|
||||
|
@ -123,11 +125,13 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
|||
SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99),
|
||||
#endif
|
||||
SCHED_TASK(compass_save, 0.1, 200, 105),
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
#if HAL_LOGGING_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108),
|
||||
#endif
|
||||
SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200, 111),
|
||||
#if HAL_LOGGING_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200, 114),
|
||||
#endif
|
||||
#if HAL_BUTTON_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117),
|
||||
#endif
|
||||
|
@ -156,7 +160,9 @@ constexpr int8_t Rover::_failsafe_priorities[7];
|
|||
Rover::Rover(void) :
|
||||
AP_Vehicle(),
|
||||
param_loader(var_info),
|
||||
#if HAL_LOGGING_ENABLED
|
||||
logger{g.log_bitmask},
|
||||
#endif
|
||||
modes(&g.mode1),
|
||||
control_mode(&mode_initializing)
|
||||
{
|
||||
|
@ -336,6 +342,7 @@ void Rover::ahrs_update()
|
|||
ground_speed = ahrs.groundspeed();
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (should_log(MASK_LOG_ATTITUDE_FAST)) {
|
||||
Log_Write_Attitude();
|
||||
Log_Write_Sail();
|
||||
|
@ -348,6 +355,7 @@ void Rover::ahrs_update()
|
|||
if (should_log(MASK_LOG_VIDEO_STABILISATION)) {
|
||||
ahrs.write_video_stabilisation();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -376,6 +384,7 @@ void Rover::gcs_failsafe_check(void)
|
|||
failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", do_failsafe);
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
/*
|
||||
log some key data - 10Hz
|
||||
*/
|
||||
|
@ -435,7 +444,7 @@ void Rover::update_logging2(void)
|
|||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
||||
/*
|
||||
once a second events
|
||||
|
|
|
@ -136,7 +136,9 @@ private:
|
|||
RC_Channel *channel_pitch;
|
||||
RC_Channel *channel_walking_height;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP_Logger logger;
|
||||
#endif
|
||||
|
||||
// flight modes convenience array
|
||||
AP_Int8 *modes;
|
||||
|
@ -226,7 +228,9 @@ private:
|
|||
static const AP_Scheduler::Task scheduler_tasks[];
|
||||
|
||||
static const AP_Param::Info var_info[];
|
||||
#if HAL_LOGGING_ENABLED
|
||||
static const LogStructure log_structure[];
|
||||
#endif
|
||||
|
||||
// time that rudder/steering arming has been running
|
||||
uint32_t rudder_arm_timer;
|
||||
|
|
|
@ -45,13 +45,6 @@
|
|||
#define CRUISE_SPEED 2 // in m/s
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Logging control
|
||||
//
|
||||
#ifndef LOGGING_ENABLED
|
||||
#define LOGGING_ENABLED ENABLED
|
||||
#endif
|
||||
|
||||
#define DEFAULT_LOG_BITMASK 0xffff
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
|
@ -45,8 +45,8 @@ void Rover::crash_check()
|
|||
}
|
||||
|
||||
if (crashed) {
|
||||
AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK,
|
||||
LogErrorCode::CRASH_CHECK_CRASH);
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK,
|
||||
LogErrorCode::CRASH_CHECK_CRASH);
|
||||
|
||||
if (is_balancebot()) {
|
||||
// send message to gcs
|
||||
|
|
|
@ -15,7 +15,9 @@ void Rover::cruise_learn_start()
|
|||
cruise_learn.throttle_filt.reset(g2.motors.get_throttle());
|
||||
cruise_learn.learn_start_ms = AP_HAL::millis();
|
||||
cruise_learn.log_count = 0;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
log_write_cruise_learn();
|
||||
#endif
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning started");
|
||||
}
|
||||
|
||||
|
@ -29,10 +31,12 @@ void Rover::cruise_learn_update()
|
|||
cruise_learn.speed_filt.apply(speed, 0.02f);
|
||||
cruise_learn.throttle_filt.apply(g2.motors.get_throttle(), 0.02f);
|
||||
// 10Hz logging
|
||||
#if HAL_LOGGING_ENABLED
|
||||
if (cruise_learn.log_count % 5 == 0) {
|
||||
log_write_cruise_learn();
|
||||
}
|
||||
cruise_learn.log_count += 1;
|
||||
#endif
|
||||
// check how long it took to learn
|
||||
if (AP_HAL::millis() - cruise_learn.learn_start_ms >= 2000) {
|
||||
cruise_learn_complete();
|
||||
|
@ -56,10 +60,13 @@ void Rover::cruise_learn_complete()
|
|||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning failed");
|
||||
}
|
||||
cruise_learn.learn_start_ms = 0;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
log_write_cruise_learn();
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// logging for cruise learn
|
||||
void Rover::log_write_cruise_learn() const
|
||||
{
|
||||
|
@ -77,3 +84,4 @@ void Rover::log_write_cruise_learn() const
|
|||
cruise_learn.speed_filt.get(),
|
||||
cruise_learn.throttle_filt.get());
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -53,7 +53,7 @@ void Rover::ekf_check()
|
|||
ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX;
|
||||
ekf_check_state.bad_variance = true;
|
||||
|
||||
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK,
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,
|
||||
LogErrorCode::EKFCHECK_BAD_VARIANCE);
|
||||
// send message to gcs
|
||||
if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) {
|
||||
|
@ -71,7 +71,7 @@ void Rover::ekf_check()
|
|||
// if variance is flagged as bad and the counter reaches zero then clear flag
|
||||
if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) {
|
||||
ekf_check_state.bad_variance = false;
|
||||
AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK,
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK,
|
||||
LogErrorCode::EKFCHECK_VARIANCE_CLEARED);
|
||||
// clear failsafe
|
||||
failsafe_ekf_off_event();
|
||||
|
@ -156,7 +156,7 @@ void Rover::failsafe_ekf_event()
|
|||
|
||||
// EKF failsafe event has occurred
|
||||
failsafe.ekf = true;
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV,
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,
|
||||
LogErrorCode::FAILSAFE_OCCURRED);
|
||||
|
||||
// does this mode require position?
|
||||
|
@ -189,7 +189,7 @@ void Rover::failsafe_ekf_off_event(void)
|
|||
}
|
||||
|
||||
failsafe.ekf = false;
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV,
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV,
|
||||
LogErrorCode::FAILSAFE_RESOLVED);
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe cleared");
|
||||
}
|
||||
|
|
|
@ -51,11 +51,11 @@ void Rover::fence_check()
|
|||
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
|
||||
}
|
||||
}
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches));
|
||||
|
||||
} else if (orig_breaches) {
|
||||
// record clearing of breach
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE,
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE,
|
||||
LogErrorCode::ERROR_RESOLVED);
|
||||
}
|
||||
#endif // AP_FENCE_ENABLED
|
||||
|
|
|
@ -512,10 +512,12 @@ void ModeAuto::send_guided_position_target()
|
|||
/********************************************************************************/
|
||||
bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd)
|
||||
{
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// log when new commands start
|
||||
if (rover.should_log(MASK_LOG_CMD)) {
|
||||
rover.logger.Write_Mission_Cmd(mission, cmd);
|
||||
}
|
||||
#endif
|
||||
|
||||
switch (cmd.id) {
|
||||
case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint
|
||||
|
|
|
@ -171,6 +171,7 @@ void ModeDock::update()
|
|||
calc_steering_from_turn_rate(desired_turn_rate);
|
||||
calc_throttle(desired_speed, true);
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// @LoggerMessage: DOCK
|
||||
// @Description: Dock mode target information
|
||||
// @Field: TimeUS: Time since system startup
|
||||
|
@ -196,6 +197,7 @@ void ModeDock::update()
|
|||
target_cm.y,
|
||||
desired_speed,
|
||||
desired_turn_rate);
|
||||
#endif
|
||||
}
|
||||
|
||||
float ModeDock::apply_slowdown(float desired_speed)
|
||||
|
|
|
@ -54,7 +54,7 @@ void Rover::init_ardupilot()
|
|||
osd.init();
|
||||
#endif
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
#if HAL_LOGGING_ENABLED
|
||||
log_init();
|
||||
#endif
|
||||
|
||||
|
@ -179,7 +179,7 @@ void Rover::startup_ground(void)
|
|||
mode_auto.mission.init();
|
||||
|
||||
// initialise AP_Logger library
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
#if HAL_LOGGING_ENABLED
|
||||
logger.setVehicle_Startup_Writer(
|
||||
FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void)
|
||||
);
|
||||
|
@ -259,8 +259,8 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
|||
Mode &old_mode = *control_mode;
|
||||
if (!new_mode.enter()) {
|
||||
// Log error that we failed to enter desired flight mode
|
||||
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE,
|
||||
LogErrorCode(new_mode.mode_number()));
|
||||
LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE,
|
||||
LogErrorCode(new_mode.mode_number()));
|
||||
gcs().send_text(MAV_SEVERITY_WARNING, "Flight mode change failed");
|
||||
return false;
|
||||
}
|
||||
|
@ -281,7 +281,9 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason)
|
|||
old_mode.exit();
|
||||
|
||||
control_mode_reason = reason;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason);
|
||||
#endif
|
||||
gcs().send_message(MSG_HEARTBEAT);
|
||||
|
||||
notify_mode(control_mode);
|
||||
|
@ -340,6 +342,7 @@ uint8_t Rover::check_digital_pin(uint8_t pin)
|
|||
return hal.gpio->read(pin);
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
/*
|
||||
should we log a message type now?
|
||||
*/
|
||||
|
@ -347,6 +350,7 @@ bool Rover::should_log(uint32_t mask)
|
|||
{
|
||||
return logger.should_log(mask);
|
||||
}
|
||||
#endif
|
||||
|
||||
// returns true if vehicle is a boat
|
||||
// this affects whether the vehicle tries to maintain position after reaching waypoints
|
||||
|
|
Loading…
Reference in New Issue