diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index c0d5caf214..05d614e4b0 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -1,6 +1,5 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduRover v2.49" /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by @@ -32,80 +31,11 @@ Please contribute your ideas! See http://dev.ardupilot.com for details */ -#include -#include -#include -#include -#include -#include -#include // ArduPilot GPS library -#include // ArduPilot Mega Analog to Digital Converter Library -#include -#include -#include // ArduPilot Mega Magnetometer Library -#include // ArduPilot Mega Vector/Matrix math Library -#include // Inertial Sensor (uncalibated IMU) Library -#include // ArduPilot Mega DCM Library -#include -#include // Mission command library -#include -#include -#include // PID library -#include // RC Channel Library -#include // Range finder library -#include // Filter library -#include // Filter library - butterworth filter -#include // FIFO buffer library -#include // Mode Filter from Filter library -#include // Mode Filter from Filter library -#include // APM relay -#include -#include // Camera/Antenna mount -#include // Camera triggering -#include // MAVLink GCS definitions -#include // Serial manager library -#include // needed for AHRS build -#include // needed for AHRS build -#include -#include // RC input mapping library -#include -#include // main loop scheduler -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include "compat.h" - -#include // Notify library -#include // Battery monitor library -#include // Optical Flow library - -// Configuration -#include "config.h" - -// Local modules -#include "defines.h" -#include "Parameters.h" -#include "GCS.h" - -#include // ArduPilot Mega Declination Helper Library - #include "Rover.h" -#include "utility/FastDelegate.h" const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; -static Rover rover; +Rover rover; #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wpmf-conversions" diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 3e802b81a3..cb16daa143 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + // default sensors are present and healthy: gyro, accelerometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control #define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS) @@ -1253,11 +1255,6 @@ void Rover::mavlink_delay_cb() in_mavlink_delay = false; } -void mavlink_delay_cb_static() -{ - rover.mavlink_delay_cb(); -} - /* * send a message on both GCS links */ diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index b69e0a2791..4eddb509cd 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + #if LOGGING_ENABLED == ENABLED #if CLI_ENABLED == ENABLED @@ -370,7 +372,7 @@ void Rover::Log_Write_Baro(void) DataFlash.Log_Write_Baro(barometer); } -static const struct LogStructure log_structure[] PROGMEM = { +const LogStructure Rover::log_structure[] PROGMEM = { LOG_COMMON_STRUCTURES, { LOG_PERFORMANCE_MSG, sizeof(log_Performance), "PM", "IIHIhhhBH", "TimeMS,LTime,MLC,gDt,GDx,GDy,GDz,I2CErr,INSErr" }, @@ -386,6 +388,20 @@ static const struct LogStructure log_structure[] PROGMEM = { "STER", "Iff", "TimeMS,Demanded,Achieved" }, }; +void Rover::log_init(void) +{ + DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0])); + if (!DataFlash.CardInserted()) { + gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted")); + g.log_bitmask.set(0); + } else if (DataFlash.NeedErase()) { + gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS")); + do_erase_logs(); + } + if (g.log_bitmask != 0) { + start_logging(); + } +} #if CLI_ENABLED == ENABLED // Read the DataFlash log memory : Packet Parser diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index 8472113db4..5f9e3cb741 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -1,5 +1,7 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + /* APMRover2 parameter definitions */ diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index 0ad1ff7aa0..6c1dfd66ea 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -17,6 +17,8 @@ main Rover class, containing all vehicle specific state */ +#include "Rover.h" + Rover::Rover(void) : param_loader(var_info), ins_sample_rate(AP_InertialSensor::RATE_50HZ), diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 2002eac84e..98e83f2a1f 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -17,6 +17,11 @@ main Rover class, containing all vehicle specific state */ +#ifndef _ROVER_H_ +#define _ROVER_H_ + +#define THISFIRMWARE "ArduRover v2.49" + #include #include @@ -365,6 +370,7 @@ private: bool gcs_out_of_time; static const AP_Param::Info var_info[]; + static const LogStructure log_structure[]; private: // private member functions @@ -414,6 +420,7 @@ private: void Log_Write_RC(void); void Log_Write_Baro(void); void Log_Read(uint16_t log_num, uint16_t start_page, uint16_t end_page); + void log_init(void); void start_logging() ; void load_parameters(void); void throttle_slew_limit(int16_t last_throttle); @@ -534,3 +541,8 @@ public: }; #define MENU_FUNC(func) AP_HAL_CLASSPROC(&rover, &Rover::func) + +extern const AP_HAL::HAL& hal; +extern Rover rover; + +#endif // _ROVER_H_ diff --git a/APMrover2/Steering.cpp b/APMrover2/Steering.cpp index f0113dafb6..d185ed7cba 100644 --- a/APMrover2/Steering.cpp +++ b/APMrover2/Steering.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + /***************************************** * Throttle slew limit *****************************************/ diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index b9c91ebd0b..ed327e1120 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + /* Functions in this file: void set_next_WP(const AP_Mission::Mission_Command& cmd) void set_guided_WP(void) diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index f72a1a4d25..a1f4c4a8bb 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -1,5 +1,7 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + /********************************************************************************/ // Command Event Handlers /********************************************************************************/ diff --git a/APMrover2/commands_process.cpp b/APMrover2/commands_process.cpp index d3505bb715..c263f56efd 100644 --- a/APMrover2/commands_process.cpp +++ b/APMrover2/commands_process.cpp @@ -1,5 +1,7 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + // called by update navigation at 10Hz // -------------------- void Rover::update_commands(void) diff --git a/APMrover2/compat.cpp b/APMrover2/compat.cpp index c79fcd7b43..5146951711 100644 --- a/APMrover2/compat.cpp +++ b/APMrover2/compat.cpp @@ -1,4 +1,4 @@ - +#include "Rover.h" void Rover::delay(uint32_t ms) { diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index 6708b50ef2..c93fd69a10 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -1,5 +1,7 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + void Rover::read_control_switch() { diff --git a/APMrover2/events.cpp b/APMrover2/events.cpp index d1f1c61706..736678d884 100644 --- a/APMrover2/events.cpp +++ b/APMrover2/events.cpp @@ -1,5 +1,6 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" void Rover::update_events(void) { diff --git a/APMrover2/failsafe.cpp b/APMrover2/failsafe.cpp index 0b879c02c2..84525ac072 100644 --- a/APMrover2/failsafe.cpp +++ b/APMrover2/failsafe.cpp @@ -4,6 +4,8 @@ Andrew Tridgell, December 2011 */ +#include "Rover.h" + /* our failsafe strategy is to detect main loop lockup and switch to passing inputs straight from the RC inputs to RC outputs. @@ -49,7 +51,3 @@ void Rover::failsafe_check() } } -static void failsafe_check_static() -{ - rover.failsafe_check(); -} diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp index 766b182a65..b0454a4db9 100644 --- a/APMrover2/navigation.cpp +++ b/APMrover2/navigation.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + //**************************************************************** // Function that will calculate the desired direction to fly and distance //**************************************************************** diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index fe54301a40..5b49599897 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + /* allow for runtime change of control channel ordering */ diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index 03332e14c3..900503f693 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + void Rover::init_barometer(void) { gcs_send_text_P(SEVERITY_LOW, PSTR("Calibrating barometer")); diff --git a/APMrover2/setup.cpp b/APMrover2/setup.cpp index 52497270d8..9aa9355126 100644 --- a/APMrover2/setup.cpp +++ b/APMrover2/setup.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + #if CLI_ENABLED == ENABLED // Command/function table for the setup menu diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 98b3849997..7e9977ef3b 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -6,6 +6,8 @@ The init_ardupilot function processes everything we need for an in - air restart *****************************************************************************/ +#include "Rover.h" + #if CLI_ENABLED == ENABLED // This is the help function @@ -63,6 +65,16 @@ void Rover::run_cli(AP_HAL::UARTDriver *port) #endif // CLI_ENABLED +static void mavlink_delay_cb_static() +{ + rover.mavlink_delay_cb(); +} + +static void failsafe_check_static() +{ + rover.failsafe_check(); +} + void Rover::init_ardupilot() { // initialise console serial port @@ -125,17 +137,7 @@ void Rover::init_ardupilot() mavlink_system.sysid = g.sysid_this_mav; #if LOGGING_ENABLED == ENABLED - DataFlash.Init(log_structure, sizeof(log_structure)/sizeof(log_structure[0])); - if (!DataFlash.CardInserted()) { - gcs_send_text_P(SEVERITY_LOW, PSTR("No dataflash card inserted")); - g.log_bitmask.set(0); - } else if (DataFlash.NeedErase()) { - gcs_send_text_P(SEVERITY_LOW, PSTR("ERASING LOGS")); - do_erase_logs(); - } - if (g.log_bitmask != 0) { - start_logging(); - } + log_init(); #endif // Register mavlink_delay_cb, which will run anytime you have diff --git a/APMrover2/test.cpp b/APMrover2/test.cpp index ce49733649..4026cedaa1 100644 --- a/APMrover2/test.cpp +++ b/APMrover2/test.cpp @@ -1,5 +1,7 @@ // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +#include "Rover.h" + #if CLI_ENABLED == ENABLED // Creates a constant array of structs representing menu options