Rover: fixed build of .cpp files

This commit is contained in:
Andrew Tridgell 2015-05-13 13:16:45 +10:00
parent 2b6835d187
commit b47a09b709
20 changed files with 73 additions and 93 deletions

View File

@ -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 <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_HAL.h>
#include <AP_Menu.h>
#include <AP_Param.h>
#include <StorageManager.h>
#include <AP_GPS.h> // ArduPilot GPS library
#include <AP_ADC.h> // ArduPilot Mega Analog to Digital Converter Library
#include <AP_ADC_AnalogSource.h>
#include <AP_Baro.h>
#include <AP_Compass.h> // ArduPilot Mega Magnetometer Library
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library
#include <AP_InertialSensor.h> // Inertial Sensor (uncalibated IMU) Library
#include <AP_AHRS.h> // ArduPilot Mega DCM Library
#include <AP_NavEKF.h>
#include <AP_Mission.h> // Mission command library
#include <AP_Rally.h>
#include <AP_Terrain.h>
#include <PID.h> // PID library
#include <RC_Channel.h> // RC Channel Library
#include <AP_RangeFinder.h> // Range finder library
#include <Filter.h> // Filter library
#include <Butter.h> // Filter library - butterworth filter
#include <AP_Buffer.h> // FIFO buffer library
#include <ModeFilter.h> // Mode Filter from Filter library
#include <AverageFilter.h> // Mode Filter from Filter library
#include <AP_Relay.h> // APM relay
#include <AP_ServoRelayEvents.h>
#include <AP_Mount.h> // Camera/Antenna mount
#include <AP_Camera.h> // Camera triggering
#include <GCS_MAVLink.h> // MAVLink GCS definitions
#include <AP_SerialManager.h> // Serial manager library
#include <AP_Airspeed.h> // needed for AHRS build
#include <AP_Vehicle.h> // needed for AHRS build
#include <DataFlash.h>
#include <AP_RCMapper.h> // RC input mapping library
#include <SITL.h>
#include <AP_Scheduler.h> // main loop scheduler
#include <stdarg.h>
#include <AP_Navigation.h>
#include <APM_Control.h>
#include <AP_L1_Control.h>
#include <AP_BoardConfig.h>
#include <AP_Frsky_Telem.h>
#include <AP_HAL_AVR.h>
#include <AP_HAL_SITL.h>
#include <AP_HAL_PX4.h>
#include <AP_HAL_VRBRAIN.h>
#include <AP_HAL_FLYMAPLE.h>
#include <AP_HAL_Linux.h>
#include <AP_HAL_Empty.h>
#include "compat.h"
#include <AP_Notify.h> // Notify library
#include <AP_BattMonitor.h> // Battery monitor library
#include <AP_OpticalFlow.h> // Optical Flow library
// Configuration
#include "config.h"
// Local modules
#include "defines.h"
#include "Parameters.h"
#include "GCS.h"
#include <AP_Declination.h> // 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"

View File

@ -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
*/

View File

@ -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

View File

@ -1,5 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
/*
APMRover2 parameter definitions
*/

View File

@ -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),

View File

@ -17,6 +17,11 @@
main Rover class, containing all vehicle specific state
*/
#ifndef _ROVER_H_
#define _ROVER_H_
#define THISFIRMWARE "ArduRover v2.49"
#include <math.h>
#include <stdarg.h>
@ -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_

View File

@ -1,5 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
/*****************************************
* Throttle slew limit
*****************************************/

View File

@ -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)

View File

@ -1,5 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Rover.h"
/********************************************************************************/
// Command Event Handlers
/********************************************************************************/

View File

@ -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)

View File

@ -1,4 +1,4 @@
#include "Rover.h"
void Rover::delay(uint32_t ms)
{

View File

@ -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()
{

View File

@ -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)
{

View File

@ -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();
}

View File

@ -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
//****************************************************************

View File

@ -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
*/

View File

@ -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"));

View File

@ -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

View File

@ -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

View File

@ -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