diff --git a/ArduRover/CarStampede.h b/ArduRover/CarStampede.h index 9cb4b6792b..0e319436de 100644 --- a/ArduRover/CarStampede.h +++ b/ArduRover/CarStampede.h @@ -41,7 +41,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD // compass orientation: See AP_Compass_HMC5843.h for possible values // battery monitoring -static const bool batteryMonitorEnabled = true; +static const bool batteryMonitorEnabled = false; static const uint8_t batteryPin = 0; static const float batteryVoltageDivRatio = 6; static const float batteryMinVolt = 10.0; diff --git a/ArduRover/ControllerCar.h b/ArduRover/ControllerCar.h index 860281790a..c1951cf786 100644 --- a/ArduRover/ControllerCar.h +++ b/ArduRover/ControllerCar.h @@ -44,6 +44,7 @@ private: _thrustCmd = _hal->rc[ch_thrust]->getRadioPosition(); } void autoLoop(const float dt) { + //_hal->debug->printf_P(PSTR("cont: ch1: %f\tch2: %f\n"),_hal->rc[ch_thrust]->getRadioPosition(), _hal->rc[ch_str]->getRadioPosition()); _strCmd = pidStr.update(_guide->getHeadingError(), _nav->getYawRate(), dt); _thrustCmd = pidThrust.update( _guide->getGroundSpeedCommand() diff --git a/apo/PlaneEasystar.h b/apo/PlaneEasystar.h index 7273922a61..54e331f84d 100644 --- a/apo/PlaneEasystar.h +++ b/apo/PlaneEasystar.h @@ -40,7 +40,7 @@ static const Matrix3f compassOrientation = AP_COMPASS_COMPONENTS_UP_PINS_FORWARD // compass orientation: See AP_Compass_HMC5843.h for possible values // battery monitoring -static const bool batteryMonitorEnabled = true; +static const bool batteryMonitorEnabled = false; static const uint8_t batteryPin = 0; static const float batteryVoltageDivRatio = 6; static const float batteryMinVolt = 10.0; diff --git a/apo/apo.pde b/apo/apo.pde index a413f824e3..cdd4455bfd 100644 --- a/apo/apo.pde +++ b/apo/apo.pde @@ -17,8 +17,8 @@ #include // Vehicle Configuration -#include "QuadArducopter.h" -//#include "PlaneEasystar.h" +//#include "QuadArducopter.h" +#include "PlaneEasystar.h" // ArduPilotOne Default Setup #include "APO_DefaultSetup.h" diff --git a/libraries/APM_BMP085/APM_BMP085.h b/libraries/APM_BMP085/APM_BMP085.h index 7b75c7c865..fb44e68a8c 100644 --- a/libraries/APM_BMP085/APM_BMP085.h +++ b/libraries/APM_BMP085/APM_BMP085.h @@ -4,7 +4,7 @@ #define TEMP_FILTER_SIZE 16 #define PRESS_FILTER_SIZE 10 -#include +#include "APM_BMP085_hil.h" class APM_BMP085_Class { diff --git a/libraries/APO/APO.h b/libraries/APO/APO.h index c39be87e2c..360b93dada 100644 --- a/libraries/APO/APO.h +++ b/libraries/APO/APO.h @@ -17,5 +17,9 @@ #include "AP_RcChannel.h" #include "AP_BatteryMonitor.h" #include "AP_ArmingMechanism.h" +#include "AP_CommLink.h" +#include "AP_Var_keys.h" +#include "constants.h" #endif /* APO_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/APO_DefaultSetup.h b/libraries/APO/APO_DefaultSetup.h index 14661b2f22..82ee0250b8 100644 --- a/libraries/APO/APO_DefaultSetup.h +++ b/libraries/APO/APO_DefaultSetup.h @@ -181,3 +181,4 @@ void loop() { } #endif //_APO_COMMON_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_ArmingMechanism.cpp b/libraries/APO/AP_ArmingMechanism.cpp index ffd7d0a886..f319a6d91e 100644 --- a/libraries/APO/AP_ArmingMechanism.cpp +++ b/libraries/APO/AP_ArmingMechanism.cpp @@ -13,7 +13,7 @@ namespace apo { void AP_ArmingMechanism::update(const float dt) { - + //_hal->debug->printf_P(PSTR("ch1: %f\tch2: %f\n"),_hal->rc[_ch1]->getRadioPosition(), _hal->rc[_ch2]->getRadioPosition()); // arming if ( (_hal->getState() != MAV_STATE_ACTIVE) && (fabs(_hal->rc[_ch1]->getRadioPosition()) < _ch1Min) && diff --git a/libraries/APO/AP_Autopilot.cpp b/libraries/APO/AP_Autopilot.cpp index e7f943d32a..07c909d637 100644 --- a/libraries/APO/AP_Autopilot.cpp +++ b/libraries/APO/AP_Autopilot.cpp @@ -5,9 +5,27 @@ * Author: jgoppert */ +/* + * AVR runtime + */ +//#include +//#include +//#include +//#include + +#include "../FastSerial/FastSerial.h" #include "AP_Autopilot.h" +#include "../AP_GPS/AP_GPS.h" +#include "../APM_RC/APM_RC.h" +#include "AP_HardwareAbstractionLayer.h" +#include "AP_CommLink.h" +#include "AP_MavlinkCommand.h" +#include "AP_Navigator.h" +#include "AP_Controller.h" +#include "AP_Guide.h" #include "AP_BatteryMonitor.h" + namespace apo { class AP_HardwareAbstractionLayer; @@ -252,3 +270,4 @@ void AP_Autopilot::callback3(void * data) { } } // apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Autopilot.h b/libraries/APO/AP_Autopilot.h index 5fa9578c92..b48737d81b 100644 --- a/libraries/APO/AP_Autopilot.h +++ b/libraries/APO/AP_Autopilot.h @@ -8,38 +8,7 @@ #ifndef AP_AUTOPILOT_H_ #define AP_AUTOPILOT_H_ -/* - * AVR runtime - */ -#include -#include -#include -#include -/* - * Libraries - */ -#include "../AP_Common/AP_Common.h" -#include "../FastSerial/FastSerial.h" -#include "../AP_GPS/GPS.h" -#include "../APM_RC/APM_RC.h" -#include "../AP_ADC/AP_ADC.h" -#include "../APM_BMP085/APM_BMP085.h" -#include "../AP_Compass/AP_Compass.h" -#include "../AP_Math/AP_Math.h" -#include "../AP_IMU/AP_IMU.h" -#include "../AP_DCM/AP_DCM.h" #include "../AP_Common/AP_Loop.h" -#include "../GCS_MAVLink/GCS_MAVLink.h" -#include "../AP_RangeFinder/AP_RangeFinder.h" -/* - * Local Modules - */ -#include "AP_HardwareAbstractionLayer.h" -#include "AP_RcChannel.h" -#include "AP_Controller.h" -#include "AP_Navigator.h" -#include "AP_Guide.h" -#include "AP_CommLink.h" /** * ArduPilotOne namespace to protect variables @@ -50,7 +19,10 @@ namespace apo { // forward declarations -class AP_CommLink; +class AP_Navigator; +class AP_Guide; +class AP_Controller; +class AP_HardwareAbstractionLayer; /** * This class encapsulates the entire autopilot system @@ -152,3 +124,4 @@ private: } // namespace apo #endif /* AP_AUTOPILOT_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_BatteryMonitor.h b/libraries/APO/AP_BatteryMonitor.h index 96b94bc46d..359320a368 100644 --- a/libraries/APO/AP_BatteryMonitor.h +++ b/libraries/APO/AP_BatteryMonitor.h @@ -49,5 +49,4 @@ private: } // namespace apo #endif /* AP_BATTERYMONITOR_H_ */ - // vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_CommLink.cpp b/libraries/APO/AP_CommLink.cpp index cdba1208b1..a18b91594a 100644 --- a/libraries/APO/AP_CommLink.cpp +++ b/libraries/APO/AP_CommLink.cpp @@ -10,6 +10,7 @@ #include "AP_Navigator.h" #include "AP_Guide.h" #include "AP_Controller.h" +#include "AP_MavlinkCommand.h" #include "AP_HardwareAbstractionLayer.h" #include "AP_RcChannel.h" #include "../AP_GPS/AP_GPS.h" @@ -719,3 +720,4 @@ uint8_t MavlinkComm::_checkTarget(uint8_t sysid, uint8_t compid) { } } // apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_CommLink.h b/libraries/APO/AP_CommLink.h index a05a00be4f..76b4c5e772 100644 --- a/libraries/APO/AP_CommLink.h +++ b/libraries/APO/AP_CommLink.h @@ -22,7 +22,7 @@ #include #include "../AP_Common/AP_Common.h" #include "../AP_Common/AP_Vector.h" -#include "AP_MavlinkCommand.h" +#include "../GCS_MAVLink/GCS_MAVLink.h" class FastSerial; diff --git a/libraries/APO/AP_Controller.cpp b/libraries/APO/AP_Controller.cpp index f9db002a78..933727a3d5 100644 --- a/libraries/APO/AP_Controller.cpp +++ b/libraries/APO/AP_Controller.cpp @@ -120,3 +120,4 @@ void AP_Controller::setMotors() { } // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Guide.h b/libraries/APO/AP_Guide.h index 9573b255b9..72a8d1b115 100644 --- a/libraries/APO/AP_Guide.h +++ b/libraries/APO/AP_Guide.h @@ -146,6 +146,4 @@ private: } // namespace apo #endif // AP_Guide_H - // vim:ts=4:sw=4:expandtab - diff --git a/libraries/APO/AP_HardwareAbstractionLayer.cpp b/libraries/APO/AP_HardwareAbstractionLayer.cpp index afa06769ab..9939e90e57 100644 --- a/libraries/APO/AP_HardwareAbstractionLayer.cpp +++ b/libraries/APO/AP_HardwareAbstractionLayer.cpp @@ -6,3 +6,4 @@ */ #include "AP_HardwareAbstractionLayer.h" +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_HardwareAbstractionLayer.h b/libraries/APO/AP_HardwareAbstractionLayer.h index 7bbb3e406b..9b3b9e2810 100644 --- a/libraries/APO/AP_HardwareAbstractionLayer.h +++ b/libraries/APO/AP_HardwareAbstractionLayer.h @@ -170,6 +170,7 @@ private: MAV_STATE _state; }; -} +} // namespace apo #endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_MavlinkCommand.cpp b/libraries/APO/AP_MavlinkCommand.cpp index e95f21572f..9fd6cd5627 100644 --- a/libraries/APO/AP_MavlinkCommand.cpp +++ b/libraries/APO/AP_MavlinkCommand.cpp @@ -5,6 +5,7 @@ * Author: jgoppert */ +#include "../FastSerial/FastSerial.h" #include "AP_MavlinkCommand.h" namespace apo { @@ -204,4 +205,5 @@ float AP_MavlinkCommand::alongTrack(const AP_MavlinkCommand & previous, AP_MavlinkCommand AP_MavlinkCommand::home = AP_MavlinkCommand(0,false); -} +} // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_MavlinkCommand.h b/libraries/APO/AP_MavlinkCommand.h index 067ad0c2d2..cf4beb47dd 100644 --- a/libraries/APO/AP_MavlinkCommand.h +++ b/libraries/APO/AP_MavlinkCommand.h @@ -12,7 +12,6 @@ #include "../AP_Common/AP_Common.h" #include "AP_Var_keys.h" #include "constants.h" -#include "../FastSerial/FastSerial.h" namespace apo { @@ -373,3 +372,4 @@ public: #endif /* AP_MAVLINKCOMMAND_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Navigator.cpp b/libraries/APO/AP_Navigator.cpp index 08abd70b67..70a2f3289c 100644 --- a/libraries/APO/AP_Navigator.cpp +++ b/libraries/APO/AP_Navigator.cpp @@ -15,6 +15,7 @@ #include "AP_Var_keys.h" #include "../AP_RangeFinder/AP_RangeFinder.h" #include "../AP_IMU/AP_IMU.h" +#include "../APM_BMP085/APM_BMP085_hil.h" #include "../APM_BMP085/APM_BMP085.h" namespace apo { @@ -204,3 +205,4 @@ void DcmNavigator::updateGpsLight(void) { } } // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_RcChannel.cpp b/libraries/APO/AP_RcChannel.cpp index 122324b563..1a88f887ce 100644 --- a/libraries/APO/AP_RcChannel.cpp +++ b/libraries/APO/AP_RcChannel.cpp @@ -100,3 +100,4 @@ float AP_RcChannel::_pwmToPosition(const uint16_t & pwm) { } } // namespace apo +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_RcChannel.h b/libraries/APO/AP_RcChannel.h index d2eea1a153..38cc05df9a 100644 --- a/libraries/APO/AP_RcChannel.h +++ b/libraries/APO/AP_RcChannel.h @@ -82,3 +82,4 @@ protected: } // apo #endif // AP_RCCHANNEL_H +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/AP_Var_keys.h b/libraries/APO/AP_Var_keys.h index 19f9508f81..40ebf99620 100644 --- a/libraries/APO/AP_Var_keys.h +++ b/libraries/APO/AP_Var_keys.h @@ -22,3 +22,4 @@ enum keys { // max 256 keys #endif +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/constants.h b/libraries/APO/constants.h index 2a4316bcb3..27f03c50b8 100644 --- a/libraries/APO/constants.h +++ b/libraries/APO/constants.h @@ -21,3 +21,4 @@ const float degInt2Rad = deg2Rad / scale_deg; // degrees x 1e7 to radians #define MAV_MODE_FAILSAFE MAV_MODE_TEST3 #endif /* CONSTANTS_H_ */ +// vim:ts=4:sw=4:expandtab diff --git a/libraries/APO/examples/ServoManual/ServoManual.pde b/libraries/APO/examples/ServoManual/ServoManual.pde index 56f2917389..d8abddc9ca 100644 --- a/libraries/APO/examples/ServoManual/ServoManual.pde +++ b/libraries/APO/examples/ServoManual/ServoManual.pde @@ -38,28 +38,28 @@ public: testPosition(2), testSign(1) { ch.push_back( new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, - 1500, 1900)); + 1500, 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); ch.push_back( new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, - 1900)); + 1900, RC_MODE_INOUT, false)); Serial.begin(115200); delay(2000); diff --git a/libraries/APO/examples/ServoSweep/ServoSweep.pde b/libraries/APO/examples/ServoSweep/ServoSweep.pde index 1f8744d793..fa6f7b746e 100644 --- a/libraries/APO/examples/ServoSweep/ServoSweep.pde +++ b/libraries/APO/examples/ServoSweep/ServoSweep.pde @@ -38,28 +38,28 @@ public: testPosition(2), testSign(1) { ch.push_back( new AP_RcChannel(rollKey, PSTR("ROLL"), APM_RC, 0, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(pitchKey, PSTR("PITCH"), APM_RC, 1, 1100, - 1500, 1900)); + 1500, 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(thrKey, PSTR("THR"), APM_RC, 2, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(yawKey, PSTR("YAW"), APM_RC, 3, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(ch5Key, PSTR("CH5"), APM_RC, 4, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(ch6Key, PSTR("CH6"), APM_RC, 5, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(ch7Key, PSTR("CH7"), APM_RC, 6, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); ch.push_back( new AP_RcChannel(ch8Key, PSTR("CH8"), APM_RC, 7, 1100, 1500, - 1900)); + 1900,RC_MODE_INOUT,false)); Serial.begin(115200); delay(2000);