Browse Source

Plane: move starting of new logs into DataFlash

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
fa39f315c6
  1. 12
      ArduPlane/AP_Arming.cpp
  2. 1
      ArduPlane/AP_Arming.h
  3. 7
      ArduPlane/Log.cpp
  4. 1
      ArduPlane/Plane.h
  5. 6
      ArduPlane/system.cpp

12
ArduPlane/AP_Arming.cpp

@ -23,18 +23,6 @@ enum HomeState AP_Arming_Plane::home_status() const @@ -23,18 +23,6 @@ enum HomeState AP_Arming_Plane::home_status() const
return plane.home_is_set;
}
bool AP_Arming_Plane::arm(uint8_t method)
{
// start logging here so we can check success or failure in
// arm_checks
if (plane.g.log_bitmask != NONE &&
!plane.DataFlash.logging_started()) {
plane.start_logging();
}
return AP_Arming::arm(method);
}
/*
additional arming checks for plane

1
ArduPlane/AP_Arming.h

@ -20,7 +20,6 @@ public: @@ -20,7 +20,6 @@ public:
AP_Param::setup_object_defaults(this, var_info);
}
bool pre_arm_checks(bool report);
bool arm(uint8_t method) override;
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }

7
ArduPlane/Log.cpp

@ -558,12 +558,6 @@ void Plane::Log_Write_Vehicle_Startup_Messages() @@ -558,12 +558,6 @@ void Plane::Log_Write_Vehicle_Startup_Messages()
gps.Write_DataFlash_Log_Startup_messages();
}
// start a new log
void Plane::start_logging()
{
DataFlash.StartUnstartedLogging();
}
/*
initialise logging subsystem
*/
@ -611,7 +605,6 @@ void Plane::Log_Write_Home_And_Origin() {} @@ -611,7 +605,6 @@ void Plane::Log_Write_Home_And_Origin() {}
void Plane::Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page) {}
#endif // CLI_ENABLED
void Plane::start_logging() {}
void Plane::log_init(void) {}
#endif // LOGGING_ENABLED

1
ArduPlane/Plane.h

@ -847,7 +847,6 @@ private: @@ -847,7 +847,6 @@ private:
void Log_Write_Vehicle_Startup_Messages();
void Log_Write_AOA_SSA();
void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page);
void start_logging();
void load_parameters(void);
void adjust_altitude_target();

6
ArduPlane/system.cpp

@ -838,11 +838,7 @@ void Plane::print_comma(void) @@ -838,11 +838,7 @@ void Plane::print_comma(void)
bool Plane::should_log(uint32_t mask)
{
#if LOGGING_ENABLED == ENABLED
if (!DataFlash.should_log(mask)) {
return false;
}
start_logging();
return true;
return DataFlash.should_log(mask);
#else
return false;
#endif

Loading…
Cancel
Save