AP_Mount: ported to AP_HAL

I do not have the hardware required to test this
This commit is contained in:
Pat Hickey 2012-11-12 13:42:33 -08:00 committed by Andrew Tridgell
parent eefb0f4515
commit 6cc231ae7d
6 changed files with 40 additions and 7 deletions

View File

@ -1,7 +1,7 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_Mount.h>
@ -171,7 +171,7 @@ const AP_Param::GroupInfo AP_Mount::var_info[] PROGMEM = {
AP_GROUPEND
};
extern RC_Channel* rc_ch[NUM_CHANNELS];
extern RC_Channel* rc_ch[8];
AP_Mount::AP_Mount(const struct Location *current_loc, GPS *&gps, AP_AHRS *ahrs, uint8_t id) :
_gps(gps)

View File

@ -18,16 +18,15 @@
* Comments: All angles in degrees * 100, distances in meters*
* unless otherwise stated. *
************************************************************/
#ifndef AP_Mount_H
#define AP_Mount_H
#ifndef __AP_MOUNT_H__
#define __AP_MOUNT_H__
#include <FastSerial.h>
#include <AP_Math.h>
#include <AP_Common.h>
#include <AP_GPS.h>
#include <AP_AHRS.h>
#include <GCS_MAVLink.h>
#include <../RC_Channel/RC_Channel_aux.h>
#include <RC_Channel.h>
class AP_Mount
{
@ -124,4 +123,5 @@ private:
AP_Vector3f _neutral_angles; ///< neutral position for mount, vector.x = roll vector.y = tilt, vector.z=pan
AP_Vector3f _control_angles; ///< GCS controlled position for mount, vector.x = roll vector.y = tilt, vector.z=pan
};
#endif
#endif // __AP_MOUNT_H__

View File

@ -0,0 +1 @@
include ../../../AP_Common/Arduino.mk

View File

@ -0,0 +1,32 @@
#include <AP_Common.h>
#include <AP_Progmem.h>
#include <AP_Param.h>
#include <AP_Math.h>
#include <AP_HAL.h>
#include <AP_GPS.h>
#include <AP_AHRS.h>
#include <AP_InertialSensor.h>
#include <AP_Compass.h>
#include <AP_Declination.h>
#include <AP_Airspeed.h>
#include <AP_ADC.h>
#include <AP_Baro.h>
#include <AP_Buffer.h>
#include <Filter.h>
#include <GCS_MAVLink.h>
#include <RC_Channel.h>
#include <AP_Mount.h>
#include <AP_HAL_AVR.h>
const AP_HAL::HAL& hal = AP_HAL_AVR_APM2;
void setup () {
hal.console->println_P(PSTR("Unit test for AP_Mount. This sketch"
"has no functionality, it only tests build."));
}
void loop () {}
AP_HAL_MAIN();