Fixed APO examples.

This commit is contained in:
James Goppert 2011-10-26 14:59:40 -04:00
parent 905200c7e4
commit 5770be6dc6
26 changed files with 69 additions and 61 deletions

View File

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

View File

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

View File

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

View File

@ -17,8 +17,8 @@
#include <WProgram.h>
// Vehicle Configuration
#include "QuadArducopter.h"
//#include "PlaneEasystar.h"
//#include "QuadArducopter.h"
#include "PlaneEasystar.h"
// ArduPilotOne Default Setup
#include "APO_DefaultSetup.h"

View File

@ -4,7 +4,7 @@
#define TEMP_FILTER_SIZE 16
#define PRESS_FILTER_SIZE 10
#include <APM_BMP085_hil.h>
#include "APM_BMP085_hil.h"
class APM_BMP085_Class
{

View File

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

View File

@ -181,3 +181,4 @@ void loop() {
}
#endif //_APO_COMMON_H
// vim:ts=4:sw=4:expandtab

View File

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

View File

@ -5,9 +5,27 @@
* Author: jgoppert
*/
/*
* AVR runtime
*/
//#include <avr/io.h>
//#include <avr/eeprom.h>
//#include <avr/pgmspace.h>
//#include <math.h>
#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

View File

@ -8,38 +8,7 @@
#ifndef AP_AUTOPILOT_H_
#define AP_AUTOPILOT_H_
/*
* AVR runtime
*/
#include <avr/io.h>
#include <avr/eeprom.h>
#include <avr/pgmspace.h>
#include <math.h>
/*
* 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

View File

@ -49,5 +49,4 @@ private:
} // namespace apo
#endif /* AP_BATTERYMONITOR_H_ */
// vim:ts=4:sw=4:expandtab

View File

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

View File

@ -22,7 +22,7 @@
#include <inttypes.h>
#include "../AP_Common/AP_Common.h"
#include "../AP_Common/AP_Vector.h"
#include "AP_MavlinkCommand.h"
#include "../GCS_MAVLink/GCS_MAVLink.h"
class FastSerial;

View File

@ -120,3 +120,4 @@ void AP_Controller::setMotors() {
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -146,6 +146,4 @@ private:
} // namespace apo
#endif // AP_Guide_H
// vim:ts=4:sw=4:expandtab

View File

@ -6,3 +6,4 @@
*/
#include "AP_HardwareAbstractionLayer.h"
// vim:ts=4:sw=4:expandtab

View File

@ -170,6 +170,7 @@ private:
MAV_STATE _state;
};
}
} // namespace apo
#endif /* AP_HARDWAREABSTRACTIONLAYER_H_ */
// vim:ts=4:sw=4:expandtab

View File

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

View File

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

View File

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

View File

@ -100,3 +100,4 @@ float AP_RcChannel::_pwmToPosition(const uint16_t & pwm) {
}
} // namespace apo
// vim:ts=4:sw=4:expandtab

View File

@ -82,3 +82,4 @@ protected:
} // apo
#endif // AP_RCCHANNEL_H
// vim:ts=4:sw=4:expandtab

View File

@ -22,3 +22,4 @@ enum keys {
// max 256 keys
#endif
// vim:ts=4:sw=4:expandtab

View File

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

View File

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

View File

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