global: use static method to construct DataFlash_Class

This commit is contained in:
Lucas De Marchi 2017-08-23 13:51:38 -07:00 committed by Francisco Ferreira
parent a25320d522
commit 53c82b4aaf
8 changed files with 10 additions and 10 deletions

View File

@ -27,7 +27,7 @@ Rover::Rover(void) :
channel_steer(nullptr), channel_steer(nullptr),
channel_throttle(nullptr), channel_throttle(nullptr),
channel_aux(nullptr), channel_aux(nullptr),
DataFlash{fwver.fw_string, g.log_bitmask}, DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
modes(&g.mode1), modes(&g.mode1),
L1_controller(ahrs, nullptr), L1_controller(ahrs, nullptr),
nav_controller(&L1_controller), nav_controller(&L1_controller),

View File

@ -128,7 +128,7 @@ void Tracker::ten_hz_logging_loop()
const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_HAL::HAL& hal = AP_HAL::get_HAL();
Tracker::Tracker(void) Tracker::Tracker(void)
: DataFlash{fwver.fw_string, g.log_bitmask} : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask))
{ {
memset(&current_loc, 0, sizeof(current_loc)); memset(&current_loc, 0, sizeof(current_loc));
memset(&vehicle, 0, sizeof(vehicle)); memset(&vehicle, 0, sizeof(vehicle));

View File

@ -23,8 +23,8 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/* /*
constructor for main Copter class constructor for main Copter class
*/ */
Copter::Copter(void) : Copter::Copter(void)
DataFlash{fwver.fw_string, g.log_bitmask}, : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
flight_modes(&g.flight_mode1), flight_modes(&g.flight_mode1),
mission(ahrs, mission(ahrs,
FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Copter::start_command, bool, const AP_Mission::Mission_Command &),

View File

@ -24,7 +24,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
constructor for main Plane class constructor for main Plane class
*/ */
Plane::Plane(void) Plane::Plane(void)
: DataFlash{fwver.fw_string, g.log_bitmask} : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask))
{ {
// C++11 doesn't allow in-class initialisation of bitfields // C++11 doesn't allow in-class initialisation of bitfields
auto_state.takeoff_complete = true; auto_state.takeoff_complete = true;

View File

@ -23,8 +23,8 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
/* /*
constructor for main Sub class constructor for main Sub class
*/ */
Sub::Sub(void) : Sub::Sub(void)
DataFlash {fwver.fw_string, g.log_bitmask}, : DataFlash(DataFlash_Class::create(fwver.fw_string, g.log_bitmask)),
mission(ahrs, mission(ahrs,
FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Sub::start_command, bool, const AP_Mission::Mission_Command &),
FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &), FUNCTOR_BIND_MEMBER(&Sub::verify_command_callback, bool, const AP_Mission::Mission_Command &),

View File

@ -71,7 +71,7 @@ public:
AP_Vehicle::FixedWing aparm; AP_Vehicle::FixedWing aparm;
AP_Airspeed airspeed; AP_Airspeed airspeed;
AP_Int32 unused; // logging is magic for Replay; this is unused AP_Int32 unused; // logging is magic for Replay; this is unused
DataFlash_Class dataflash{"Replay v0.1", unused}; DataFlash_Class dataflash = DataFlash_Class::create("Replay v0.1", unused);
private: private:
Parameters g; Parameters g;

View File

@ -72,7 +72,7 @@ public:
private: private:
AP_Int32 log_bitmask; AP_Int32 log_bitmask;
DataFlash_Class dataflash{"DF AllTypes 0.1", log_bitmask}; DataFlash_Class dataflash = DataFlash_Class::create("DF AllTypes 0.1", log_bitmask);
void print_mode(AP_HAL::BetterStream *port, uint8_t mode); void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
void Log_Write_TypeMessages(); void Log_Write_TypeMessages();

View File

@ -36,7 +36,7 @@ public:
private: private:
AP_Int32 log_bitmask; AP_Int32 log_bitmask;
DataFlash_Class dataflash{"DF Test 0.1", log_bitmask}; DataFlash_Class dataflash = DataFlash_Class::create("DF Test 0.1", log_bitmask);
void print_mode(AP_HAL::BetterStream *port, uint8_t mode); void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
}; };