Revision: 3659
Author:
robert.d...@gmail.com
Date: Mon Jun 15 09:42:26 2015 UTC
Log: MatrixPilot_trunk: add sub-configuration files as used in SILSIM
test builds (configured for the Cessna-172)
https://code.google.com/p/gentlenav/source/detail?r=3659
Added:
/trunk/Config/Cessna/FSconfig.h
/trunk/Config/Cessna/airspeed_options.h
/trunk/Config/Cessna/magnetometerOptions.h
/trunk/Config/Cessna/mavlink_options.h
/trunk/Config/Cessna/nv_memory_options.h
/trunk/Config/Cessna/options_auav3.h
/trunk/Config/Cessna/osd_config.h
/trunk/Config/Cessna/ports_config.h
/trunk/Tools/Build/template.sln
Modified:
/trunk/MatrixPilot/servoMix.c
/trunk/Tools/Build/proj_gen.bat
/trunk/build-all.bat
/trunk/libSTM/syscalls.c
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/FSconfig.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,238 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2011 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+#ifndef _FSCONFIG_H_
+#define _FSCONFIG_H_
+
+#include "HardwareProfile.h"
+
+#ifdef USE_AT45D_FLASH
+//#warning USE_AT45D_FLASH
+#include "../libFlashFS/MDD_AT45D.h"
+#elif defined USE_EEPROM_FLASH
+//#warning USE_EEPROM_FLASH
+#define USE_I2C1_DRIVER 1
+#include "../libFlashFS/MDD_EEPROM.h"
+#elif defined(USE_SD_INTERFACE_WITH_SPI)
+//#warning USE_SD_INTERFACE_WITH_SPI
+#include "MDD-File-System/SD-SPI.h"
+#else
+#error Must define a file system media interface
+#endif // USE_AT45D_FLASH
+
+
+// The FS_MAX_FILES_OPEN #define is only applicable when Dynamic
+// memeory allocation is not used (FS_DYNAMIC_MEM not defined).
+// Defines how many concurent open files can exist at the same time.
+// Takes up static memory. If you do not need to open more than one
+// file at the same time, then you should set this to 1 to reduce
+// memory usage
+#define FS_MAX_FILES_OPEN 3
+
+// The size of a sector
+// Must be 512, 1024, 2048, or 4096
+// 512 bytes is the value used by most cards
+#define MEDIA_SECTOR_SIZE 512
+
+
+// Uncomment this to use the FindFirst, FindNext, and FindPrev
+#define ALLOW_FILESEARCH
+
+// Comment this line out if you don't intend to write data to the card
+#define ALLOW_WRITES
+
+// Comment this line out if you don't intend to format your card
+// Writes must be enabled to use the format function
+//#define ALLOW_FORMATS
+
+// Uncomment this definition if you're using directories
+// Writes must be enabled to use directories
+//#define ALLOW_DIRS
+
+// Allows the use of the FSfprintf function
+// Writes must be enabled to use the FSprintf function
+//#define ALLOW_FSFPRINTF
+
+// If FAT32 support required then uncomment the following
+//#define SUPPORT_FAT32
+
+
+// Select how you want the timestamps to be updated
+// Use the Real-time clock peripheral to set the clock
+// You must configure the RTC in your application code
+//#define USEREALTIMECLOCK
+
+// The user will update the timing variables manually using the
SetClockVars function
+// The user should set the clock before they create a file or directory
(Create time),
+// and before they close a file (last access time, last modified time)
+//#define USERDEFINEDCLOCK
+
+// Just increment the time- this will not produce accurate times and dates
+#define INCREMENTTIMESTAMP
+
+#ifndef USEREALTIMECLOCK
+ #ifndef USERDEFINEDCLOCK
+ #ifndef INCREMENTTIMESTAMP
+ #error Please enable USEREALTIMECLOCK, USERDEFINEDCLOCK, or
INCREMENTTIMESTAMP
+ #endif
+ #endif
+#endif
+
+/************************************************************************/
+// Define FS_DYNAMIC_MEM to use malloc for allocating
+// FILE structure space. uncomment all three lines
+/************************************************************************/
+#if 0
+ #define FS_DYNAMIC_MEM
+ #ifdef USE_PIC18
+ #define FS_malloc SRAMalloc
+ #define FS_free SRAMfree
+ #else
+ #define FS_malloc malloc
+ #define FS_free free
+ #endif
+#endif
+
+// Function definitions
+// Associate the physical layer functions with the correct physical layer
+
+#ifdef USE_SD_INTERFACE_WITH_SPI // SD-SPI.c and .h
+
+// Description: Function pointer to the Media Initialize Physical Layer
function
+#define MDD_MediaInitialize MDD_SDSPI_MediaInitialize
+
+// Description: Function pointer to the Media Detect Physical Layer
function
+#define MDD_MediaDetect MDD_SDSPI_MediaDetect
+
+// Description: Function pointer to the Sector Read Physical Layer function
+#define MDD_SectorRead MDD_SDSPI_SectorRead
+
+// Description: Function pointer to the Sector Write Physical Layer
function
+#define MDD_SectorWrite MDD_SDSPI_SectorWrite
+
+// Description: Function pointer to the I/O Initialization Physical Layer
function
+#define MDD_InitIO MDD_SDSPI_InitIO
+
+// Description: Function pointer to the Media Shutdown Physical Layer
function
+#define MDD_ShutdownMedia MDD_SDSPI_ShutdownMedia
+
+// Description: Function pointer to the Write Protect Check Physical Layer
function
+#define MDD_WriteProtectState MDD_SDSPI_WriteProtectState
+
+// Description: Function pointer to the Read Capacity Physical Layer
function
+#define MDD_ReadCapacity MDD_SDSPI_ReadCapacity
+
+// Description: Function pointer to the Read Sector Size Physical Layer
Function
+#define MDD_ReadSectorSize MDD_SDSPI_ReadSectorSize
+
+#elif defined USE_AT45D_FLASH
+
+#define MDD_MediaInitialize MDD_AT45D_MediaInitialize
+#define MDD_MediaDetect MDD_AT45D_MediaDetect
+#define MDD_SectorRead MDD_AT45D_SectorRead
+#define MDD_SectorWrite MDD_AT45D_SectorWrite
+#define MDD_InitIO MDD_AT45D_InitIO
+#define MDD_ShutdownMedia MDD_AT45D_ShutdownMedia
+#define MDD_WriteProtectState MDD_AT45D_WriteProtectState
+#define MDD_ReadSectorSize MDD_AT45D_ReadSectorSize
+#define MDD_ReadCapacity MDD_AT45D_ReadCapacity
+
+//
---------------------------------------------------------------------------------------
+// The size (in number of sectors) of the desired usable data portion of
the MSD volume
+//
---------------------------------------------------------------------------------------
+// Note1: Windows 7 appears to require a minimum capacity of at least 13
sectors.
+// Note2: Windows will not be able to format a drive if it is too small.
The reason
+// for this, is that Windows will try to put a "heavyweight"
(comparatively) filesystem
+// on the drive, which will consume ~18kB of overhead for the
filesystem. If the total
+// drive size is too small to fit the filesystem, then Windows will give
an error.
+// This also means that formatting the drive will "shrink" the usuable
data storage
+// area, since the default FAT12 filesystem implemented in the Files.c
data tables is very
+// lightweight, with very low overhead.
+// Note3: It is important to make sure that no part of the MSD volume
shares a flash
+// erase page with the firmware program memory. This can be done by
using a custom
+// modified linker script, or by carefully selecting the starting address
and the
+// total size of the MSD volume. See also below code comments.
+// Note4: It is also important to make sure that no part of the MSD volume
shares
+// an erase page with the erase page that contains the microcontroller's
configuration
+// bits (for microcontrollers that use flash for storing the
configuration bits,
+// see device datasheet). This can be accomplished by using a modified
linker script,
+// which protects the flash page with the configuration bits (if
applicable), or,
+// by carefully choosing the FILES_ADDRESS and
MDD_AT45D_FLASH_DRIVE_CAPACITY,
+// to make sure the MSD volume does extend into the erase page with the
configuration
+// bits.
+
+//#define MDD_AT45D_FLASH_DRIVE_CAPACITY 14
+//#define MDD_AT45D_FLASH_DRIVE_CAPACITY 42
+#define MDD_AT45D_FLASH_DRIVE_CAPACITY 8192
+
+
+//
--------------------------------------------------------------------------
+// Starting Address of the MSD Volume.
+//
--------------------------------------------------------------------------
+// Note: Make certain that this starting address is aligned with the start
+// of a flash erase block. It is important to make certain that no part
of
+// the MSD volume overlaps any portion of a flash erase page which is used
+// for storing firmware program code. When the host writes a sector to
the
+// MSD volume, the firmware must erase an entire page of flash in order to
+// do the write. If the sector being written happened to share a flash
erase
+// page with this firmware, unpredictable results would occur, since part
of
+// firmware would also end up getting erased during the write to the MSD
volume.
+
+#define FILES_ADDRESS 0x2000
+
+
+//
--------------------------------------------------------------------------
+// Maximum files supported
+//
--------------------------------------------------------------------------
+// MDD_AT45D_FLASH_MAX_NUM_FILES_IN_ROOT must be a multiple of 16
+// Note: Even if MDD_AT45D_FLASH_MAX_NUM_FILES_IN_ROOT is 16, this does not
+// necessarily mean the drive will always work with 16 files. The drive
will
+// suppport "up to" 16 files, but other limits could be hit first, even
before
+// the drive is full. The RootDirectory0[] sector could get full with
less
+// files, especially if the files are using long filenames.
+
+//#define MDD_AT45D_FLASH_MAX_NUM_FILES_IN_ROOT 16
+#define MDD_AT45D_FLASH_MAX_NUM_FILES_IN_ROOT 64
+
+//#define AT45D_FLASH_WRITE_PROTECT
+
+#elif defined USE_EEPROM_FLASH
+
+#define MDD_MediaInitialize MDD_EEPROM_MediaInitialize
+#define MDD_MediaDetect MDD_EEPROM_MediaDetect
+#define MDD_SectorRead MDD_EEPROM_SectorRead
+#define MDD_SectorWrite MDD_EEPROM_SectorWrite
+#define MDD_InitIO MDD_EEPROM_InitIO
+#define MDD_ShutdownMedia MDD_EEPROM_ShutdownMedia
+#define MDD_WriteProtectState MDD_EEPROM_WriteProtectState
+#define MDD_ReadSectorSize MDD_EEPROM_ReadSectorSize
+#define MDD_ReadCapacity MDD_EEPROM_ReadCapacity
+
+//#define MDD_EEPROM_FLASH_DRIVE_CAPACITY 14
+#define MDD_EEPROM_FLASH_MAX_NUM_FILES_IN_ROOT 16
+
+#else
+
+#error Must define a file system media interface
+
+#endif
+
+#endif // _FSCONFIG_H_
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/airspeed_options.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,53 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2011 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+#ifndef AIRSPEED_OPTIONS_H
+#define AIRSPEED_OPTIONS_H
+
+
+// Airspeeds in m/s
+#define MINIMUM_GROUNDSPEED 3.0
+#define MINIMUM_AIRSPEED 7.0
+#define MAXIMUM_AIRSPEED 20.0
+#define CRUISE_AIRSPEED 12.0 // Gliding airspeed when
aircraft is level
+
+// Cruise airspeed may be below minimum airspeed for high drag aircraft.
+
+// Gliding airspeed control
+// Must use ALTITUDE_GAINS_VARIABLE=1 with this option.
+#define GLIDE_AIRSPEED_CONTROL 0
+
+// Pitch feedforward for gliding airspeed
+// linearly interpolated from cruise airspeed to min and max airspeed
+#define AIRSPEED_PITCH_MIN_ASPD 0.0 // Default off, start with 5.0
+#define AIRSPEED_PITCH_MAX_ASPD 0.0 // Default off, start with
-10.0
+
+// Maximum rate of pitch demand change in deg/s. Used to make control
smoother.
+// Default 10.0, Higher for small aircraft. Too low may cause instability.
+// Maximum value is 720deg/s.
+#define AIRSPEED_PITCH_ADJ_RATE 10.0
+
+// Airspeed error integrator
+#define AIRSPEED_PITCH_KI 0.04 // Integrataion rate. High =
unstable, low = slow response.
+#define AIRSPEED_PITCH_KI_MAX 0.0 // Limit of integration
control in degrees. Start with 5.0.
+
+
+#endif // AIRSPEED_OPTIONS_H
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/magnetometerOptions.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,275 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2011 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+// To do: select magnetometer type, set MAGNETICDECLINATION,
+// and select orientation of the magnetometer, and remove the next 3 lines.
+#if (MAG_YAW_DRIFT == 1 && HILSIM != 1)
+#warning "Check magnetometer options."
+#endif
+
+// Define which magnetometer you are using by uncommenting one
+// of the #define lines below.
+// HMC5843 is the 3DRobotics HMC5843 (now out of production).
+// HMC5883L is the 3DRobotics HMC5883L
+// HMC5883L_SF is the SparkFun HMC5883L
+
+//#define HMC5843
+#define HMC5883L
+//#define HMC5883L_SF
+
+// Define magneticDeclination to be the magnectic declination, in degrees,
measured
+// clockwise from the north, east is plus, west is minus.
+// Mississauga, ON is Lat 45.58 N and Long 79.65 W, Mag. Decl. therefore
is 10deg21' W or -10.35 degrees
+// Bennet Field Springvale, ON is Lat 42deg58' N and Long 80deg9' W, Mag.
Decl. therefore is 9deg48' W or -9.48 degrees
+ //Salinas, CA Magnetic Variation: 16E (1980),
http://www.airport-data.com/airport/SNS/
+#define MAGNETICDECLINATION 0
+
+// Set to 0 for fixed declination angle or 1 for variable declination angle
+#define DECLINATIONANGLE_VARIABLE 0
+
+
+// #define LED_RED_MAG_CHECK 1 if you want the RED LED to indicate the
magnetometer is not working.
+// #define LED_RED_MAG_CHECK 0 if you want the RED LED to indicate control
mode.
+
+#define LED_RED_MAG_CHECK 0
+
+////////////////////////////////////////////////////////////////////////////////
+// Uncomment one of the defines below to specify orientation of the mag.
+// The following 4 supported orientations have the mag level with the
ground.
+// MAG_FORWARDS: Component-side up, edge connector front
+// MAG_BACKWARDS: Component-side up, edge connector back
+// MAG_INVERTED: Component-side down, edge connector front
+// MAG_FLIPPED: Component-side down, edge connector back
+// MAG_DIRECT: Magnetometer mounted in an orientation that permits a
direct connection to a UDB4 or UDB5
+// Note: right now, if MAG_DIRECT is selected, UDB board orientation must
be ORIENTATION_FORWARDS
+// For 3DRobotics mags, for MAG_DIRECT the mag mounts over the UDB,
component side down.
+// For SparkFun HMC5883L, for MAG_DIRECT the mag mounts over the UDB,
component side up.
+
+#define MAG_FORWARDS
+//#define MAG_BACKWARDS
+//#define MAG_INVERTED
+//#define MAG_FLIPPED
+//#define MAG_DIRECT
+
+
+
+// ************************************************************************
+// *** Users should not need to change anything below here ****************
+// ************************************************************************
+
+
+
+// Define the alignment of magnetometer with the UDB X, Y, and Z axis.
+// MAG_X_AXIS, MAG_Y_AXIS, MAG_Y_AXIS refer to the UDB X, Y, and Z axis.
+// 0, 1, 2 refer to the magnetometer X, Y, and Z axis.
+// Each axis entry pairs a UDB axis with a magnetometer axis.
+// Each sign definition expresses the relative sign of alignment with a
UDB axis
+
+// The following definitions are for Jordi's breakout board.
+// It assumes that the X and Y axis labels on the breakout board align
+// with the X and Y labels on the UDB, and that the breakout board is
mounted with
+// the magnetometer on top, the same as for the UDB.
+
+// If you are using a different HMC5843 magnetometer breakout board, just
make sure the magnetometer
+// is aligned with the CPU chip on the UDB, with the pin 1 markers in the
same orientation
+
+
+// old 3DRobotics mag
+#ifdef HMC5843
+
+#ifdef MAG_FORWARDS
+#define MAG_X_AXIS 1
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_DIRECT
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 1
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN +
+#endif
+
+#ifdef MAG_BACKWARDS
+#define MAG_X_AXIS 1
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_INVERTED
+#define MAG_X_AXIS 1
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN +
+#endif
+
+#ifdef MAG_FLIPPED
+#define MAG_X_AXIS 1
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN +
+#endif
+
+#define MAG_GAIN 700.0
+#endif
+
+// new 3D Robotics mag
+#ifdef HMC5883L
+
+#ifdef MAG_FORWARDS
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_DIRECT
+#define MAG_X_AXIS 2
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN +
+#endif
+
+#ifdef MAG_BACKWARDS
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_INVERTED
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN +
+#endif
+
+#ifdef MAG_FLIPPED
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN +
+#endif
+
+#define MAG_GAIN 1000.0
+#endif
+
+// SparkFun HMC5883L mag
+#ifdef HMC5883L_SF
+
+#ifdef MAG_FORWARDS
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_DIRECT
+#define MAG_X_AXIS 2
+#define MAG_Y_AXIS 0
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_BACKWARDS
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN -
+#endif
+
+#ifdef MAG_INVERTED
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN -
+#define MAG_Y_SIGN -
+#define MAG_Z_SIGN +
+#endif
+
+#ifdef MAG_FLIPPED
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 2
+#define MAG_Z_AXIS 1
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN +
+#endif
+
+#define MAG_GAIN 1000.0
+#endif
+
+#if (HILSIM == 1)
+#undef MAG_X_AXIS
+#undef MAG_Y_AXIS
+#undef MAG_Z_AXIS
+#undef MAG_X_SIGN
+#undef MAG_Y_SIGN
+#undef MAG_Z_SIGN
+#undef MAG_GAIN
+#define MAG_X_AXIS 0
+#define MAG_Y_AXIS 1
+#define MAG_Z_AXIS 2
+#define MAG_X_SIGN +
+#define MAG_Y_SIGN +
+#define MAG_Z_SIGN +
+
+#define MAG_GAIN 1000.0
+#endif
+
+// Minimum and maximum values expected for the absolute value of the
magnetic field.
+// These are used to help detect when the magnetometer has stopped working
properly due to
+// RF interference that may put it into an unknown state.
+
+#define MAGNETICMINIMUM 300
+#define MAGNETICMAXIMUM 1500
+
+// The following line computes an internal parameter, do not change it.
+#define DECLINATIONANGLE ((int16_t)(MAGNETICDECLINATION *(32767.0 /
180.0)))
+
+
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/mavlink_options.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,64 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2011 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+////////////////////////////////////////////////////////////////////////////////
+// mavlink_options.h
+//
+
+#ifndef USE_MAVLINK
+#define USE_MAVLINK 1
+#endif
+
+// MAVLink requires an aircraft Identifier (I.D) as it is designed to
control multiple aircraft
+// Each aircraft in the sky will need a unique I.D. in the range from 0-255
+#define MAVLINK_SYSID 1
+
+// Common data rates
+#define MAVLINK_RATE_RC_CHAN 0 // RC_CHANNELS_SCALED,
RC_CHANNELS_RAW, SERVO_OUTPUT_RAW |
+#define MAVLINK_RATE_IMU_RAW 0 //
ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT,
NAV_CONTROLLER_OUTPUT. |
+#define MAVLINK_RATE_POSITION 8 // LOCAL_POSITION,
GLOBAL_POSITION/GLOBAL_POSITION_INT messages. |
+#define MAVLINK_RATE_RAW_SENSORS 2 // IMU_RAW, GPS_RAW,
GPS_STATUS packets.
+
+// Fixed data rates
+#define MAVLINK_RATE_HEARTBEAT 4
+#define MAVLINK_RATE_SYSTEM_STATUS 4
+
+// Matrixpilot specific data rates
+#define MAVLINK_RATE_SUE 8 // SERIAL_UDB_EXTRA data
rate on channel EXTRA1
+#define MAVLINK_RATE_FORCE 4 // Send FORCE on plane
(Aerodynamic force)
+#define MAVLINK_RATE_POSITION_SENSORS 0 // Using channel EXTRA2
+
+// Send VFR_HUD message at position rate, 1=yes, 0=no. Needed for correct
mavproxy state
+#define MSG_VFR_HUD_WITH_POSITION 1
+
+#define MAVLINK_FRAME_FREQUENCY 40
+#define MAVLINK_WAYPOINT_TIMEOUT 120 // Dependent on frequency
of calling mavlink_output_40hz. 120 is 3 second timeout.
+
+// 19200,38400,57600,115200,230400,460800,921600
+// Fixed 19200 for non free running clock
+//#define MAVLINK_BAUD 19200 // now using
SERIAL_BAUDRATE in options.h
+//#define MAVLINK_BAUD 115200
+
+// Include code to remove rounding errors on PID values when using
QGroundControl
+// 1 = Yes, 0 = No
+#define QGROUNDCTONROL_PID_COMPATIBILITY 1
+
+#define MAVLINK_EXTERNAL_RX_STATUS 1
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/nv_memory_options.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,56 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2012 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+#ifndef NV_MEMORY_OPTIONS_H
+#define NV_MEMORY_OPTIONS_H
+
+////////////////////////////////////////////////////////////////////////////////
+// Use I2C port 1 drivers
+// Set to 1 to use and 0 to not include
+// WARNING: Use on UDB4+ only
+//#ifndef USE_I2C1_DRIVER
+//#define USE_I2C1_DRIVER 0
+//#endif
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Use non volatile memory to store and recall settings
+// Set to 1 to include non volatile memory service in compilation
+// WARNING: Use on UDB4+ only
+// WARNING: Can only be used with SERIAL_MAVLINK and USE_I2C1_DRIVER
+#define USE_NV_MEMORY 0
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Manual erase / format of non volatile memory table
+// If set to 1, does manual erase of memory table when it runs.
+// Use to go back to all hard coded defaults.
+// Reset to 0 after clearing to use the non volatile memory again.
+#define MANUAL_ERASE_TABLE 0
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Use variable data width in HILSIM for output channels
+// This is used to support NUM_OUTPUTS > 8
+// NOTE: Must have correct version of HILSIM to support this
+#define USE_VARIABLE_HILSIM_CHANNELS 0
+
+#endif //NV_MEMORY_OPTIONS_H
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/options_auav3.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,62 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2012 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+////////////////////////////////////////////////////////////////////////////////
+// AUAV3 only options
+
+////////////////////////////////////////////////////////////////////////////////
+// At present, the AUAV3 schematic and 'installation & basic connections'
document
+// are drafts and hence there is some inconsistency in labelling
conventions.
+//
+// The following standard labelling convention is proposed.
+//
+// AUAV3 schematic:
+// TLM - PORT1
+// OSD - PORT2
+// UART3 - PORT3
+// GPS - PORT4
+//
+// 'AUAV3 Installation and Basic Connections' document:
+// OUART1 - PORT1
+// OUART2 - PORT2
+// UART3 - PORT3
+// GPS - PORT4
+//
+////////////////////////////////////////////////////////////////////////////////
+// On the AUAV3, the external UART connections are known as ports 1
through 4.
+// The definitions below specifies which feature maps to an external port.
+//
+// NOTE: on the AUAV3, do not confuse the CONSOLE_UART definition with the
+// external port assignment.
+// Assign the console to an internal UART with CONSOLE_UART, map this
console to
+// external port connection with DBG_PORT.
+//#define GPS_PORT 4
+//#define TLM_PORT 3
+//#define DBG_PORT 1
+
+// Set this to 1 to enable the USB stack on AUAV3
+//#define USE_USB 1
+
+// Set this to 1 to enable the Mass Storage Driver support over USB on
AUAV3
+//#define USE_MSD 1
+
+// Set this to 1 to enable the UART communications support over USB on
AUAV3
+//#define USE_CDC 1
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/osd_config.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,38 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2011 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+// define the OSD types
+#define OSD_NONE 0 // OSD disabled
+#define OSD_NATIVE 1 // native OSD
+#define OSD_REMZIBI 2 // Output data formatted to use as input
to a Remzibi OSD
+#define OSD_MINIM 3 // Output data formatted for minim OSD
+
+
+// define USE_OSD to one of the types above to enables that system
+#define USE_OSD OSD_NONE
+//#define USE_OSD OSD_NATIVE
+//#define USE_OSD OSD_REMZIBI
+//#define USE_OSD OSD_MINIM
+
+
+// OSD_NATIVE development options:
+#define USE_OSD_SPI 0 // set this to 1 to use the SPI peripheral, 0
to bit-bash
+#define OSD_SF 5 // scale factor for SPI delays - TODO: get rid
of
=======================================
--- /dev/null
+++ /trunk/Config/Cessna/ports_config.h Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,69 @@
+// This file is part of MatrixPilot.
+//
+//
http://code.google.com/p/gentlenav/
+//
+// Copyright 2009-2014 MatrixPilot Team
+// See the AUTHORS.TXT file for a list of authors of MatrixPilot.
+//
+// MatrixPilot is free software: you can redistribute it and/or modify
+// it under the terms of the GNU General Public License as published by
+// the Free Software Foundation, either version 3 of the License, or
+// (at your option) any later version.
+//
+// MatrixPilot is distributed in the hope that it will be useful,
+// but WITHOUT ANY WARRANTY; without even the implied warranty of
+// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+// GNU General Public License for more details.
+//
+// You should have received a copy of the GNU General Public License
+// along with MatrixPilot. If not, see <
http://www.gnu.org/licenses/>.
+
+
+////////////////////////////////////////////////////////////////////////////////
+// The UDB4/5 has two UART's, while the AUAV3 has four UART's.
+// Three MatrixPilot features are currently defined for using a UART.
+// These being the GPS, Telemetry and a 'debug' console.
+// Therefore UDB4/5 is one UART short, the AUAV3 has one UART extra.
+//
+// CONSOLE_UART specfies which UART is used for stdio support, aka the
console.
+// Set CONSOLE_UART to 1, 2, 3 or 4 to enable the console on UART of that
number.
+// Setting CONSOLE_UART to 0 disables console support.
+// On the UDB4/5, optionally specifying console support on UART 1 or 2
overrides
+// the default usage of that UART, being the GPS and Telemetry
respectively.
+// CONSOLE_UART 3 and 4 options are only available with the AUAV3 board.
+// Thus UDB4/5 options are 0, 1, or 2 AUAV3 options are 0, 3, or 4
+// Set to 9 in order to use the USB for the console connection
+//#define CONSOLE_UART 3
+//#define OSD_UART 4
+
+
+////////////////////////////////////////////////////////////////////////////////
+// AUAV3 only options
+
+////////////////////////////////////////////////////////////////////////////////
+// At present, the AUAV3 schematic and 'installation & basic connections'
document
+// are drafts and hence there is some inconsistency in labelling
conventions.
+//
+// The following standard labelling convention is proposed.
+//
+// AUAV3 schematic:
+// TLM - PORT1
+// OSD - PORT2
+// UART3 - PORT3
+// GPS - PORT4
+//
+// 'AUAV3 Installation and Basic Connections' document:
+// OUART1 - PORT1
+// OUART2 - PORT2
+// UART3 - PORT3
+// GPS - PORT4
+//
+////////////////////////////////////////////////////////////////////////////////
+// On the AUAV3, the external UART connections are known as ports 1
through 4.
+// The definitions below specifies which feature maps to an external port.
+//
+// NOTE: on the AUAV3, do not confuse the CONSOLE_UART definition with the
+// external port assignment.
+// Assign the console to an internal UART with CONSOLE_UART, map this
console to
+// external port connection with DBG_PORT.
+
=======================================
--- /dev/null
+++ /trunk/Tools/Build/template.sln Mon Jun 15 09:42:26 2015 UTC
@@ -0,0 +1,20 @@
+
+Microsoft Visual Studio Solution File, Format Version 11.00
+# Visual C++ Express 2010
+Project("{8BC9CEB8-8B4A-11D0-8D11-00A0C91BC942}")
= "%%PROJECT%%", "%%PROJECT%%.vcxproj", "{81C72BCE-FAF2-423A-B311-50BA1F7A010D}"
+EndProject
+Global
+ GlobalSection(SolutionConfigurationPlatforms) = preSolution
+ Debug|Win32 = Debug|Win32
+ Release|Win32 = Release|Win32
+ EndGlobalSection
+ GlobalSection(ProjectConfigurationPlatforms) = postSolution
+ {81C72BCE-FAF2-423A-B311-50BA1F7A010D}.Debug|Win32.ActiveCfg = Debug|
Win32
+ {81C72BCE-FAF2-423A-B311-50BA1F7A010D}.Debug|Win32.Build.0 = Debug|Win32
+ {81C72BCE-FAF2-423A-B311-50BA1F7A010D}.Release|Win32.ActiveCfg = Release|
Win32
+ {81C72BCE-FAF2-423A-B311-50BA1F7A010D}.Release|Win32.Build.0 = Release|
Win32
+ EndGlobalSection
+ GlobalSection(SolutionProperties) = preSolution
+ HideSolutionNode = FALSE
+ EndGlobalSection
+EndGlobal
=======================================
--- /trunk/MatrixPilot/servoMix.c Wed May 6 15:02:33 2015 UTC
+++ /trunk/MatrixPilot/servoMix.c Mon Jun 15 09:42:26 2015 UTC
@@ -131,7 +131,7 @@
udb_pwOut[THROTTLE_OUTPUT_CHANNEL] = udb_servo_pulsesat(temp);
}
}
-#endif
+#endif // AIRFRAME_VTAIL
// Delta-Wing airplane airframe
// Mix roll_control, pitch_control, and waggle into aileron and elevator
@@ -160,7 +160,7 @@
temp = pwManual[THROTTLE_INPUT_CHANNEL] +
REVERSE_IF_NEEDED(THROTTLE_CHANNEL_REVERSED, throttle_control);
udb_pwOut[THROTTLE_OUTPUT_CHANNEL] = udb_servo_pulsesat(temp);
}
-#endif
+#endif // AIRFRAME_DELTA
// Helicopter airframe
// Mix half of roll_control and half of pitch_control into aileron
channels
@@ -191,7 +191,7 @@
temp = pwManual[THROTTLE_INPUT_CHANNEL] +
REVERSE_IF_NEEDED(THROTTLE_CHANNEL_REVERSED, throttle_control);
udb_pwOut[THROTTLE_OUTPUT_CHANNEL] = udb_servo_pulsesat(temp);
}
-#endif
+#endif // AIRFRAME_HELI
udb_pwOut[PASSTHROUGH_A_OUTPUT_CHANNEL] =
udb_servo_pulsesat(pwManual[PASSTHROUGH_A_INPUT_CHANNEL]);
udb_pwOut[PASSTHROUGH_B_OUTPUT_CHANNEL] =
udb_servo_pulsesat(pwManual[PASSTHROUGH_B_INPUT_CHANNEL]);
=======================================
--- /trunk/Tools/Build/proj_gen.bat Thu May 7 07:37:50 2015 UTC
+++ /trunk/Tools/Build/proj_gen.bat Mon Jun 15 09:42:26 2015 UTC
@@ -1,17 +1,19 @@
@echo off
-pyProjectCreator.py -r ../.. -t SIL -c Config/Cessna
+pyProjectCreator.py -r ../.. -n MatrixPilot -t SIL -c Config/Cessna
-pyProjectCreator.py -r ../.. -t SIL
-pyProjectCreator.py -r ../.. -t PX4
-pyProjectCreator.py -r ../.. -t UDB4
-pyProjectCreator.py -r ../.. -t UDB5
-pyProjectCreator.py -r ../.. -t AUAV3
+pyProjectCreator.py -r ../.. -n MatrixPilot -t SIL
+pyProjectCreator.py -r ../.. -n MatrixPilot -t PX4
+pyProjectCreator.py -r ../.. -n MatrixPilot -t UDB4
+pyProjectCreator.py -r ../.. -n MatrixPilot -t UDB5
+pyProjectCreator.py -r ../.. -n MatrixPilot -t AUAV3
+pyProjectCreator.py -r ../.. -n RollPitchYaw -t PX4
pyProjectCreator.py -r ../.. -n RollPitchYaw -t UDB4
pyProjectCreator.py -r ../.. -n RollPitchYaw -t UDB5
pyProjectCreator.py -r ../.. -n RollPitchYaw -t AUAV3
+pyProjectCreator.py -r ../.. -n LedTest -t PX4
pyProjectCreator.py -r ../.. -n LedTest -t UDB4
pyProjectCreator.py -r ../.. -n LedTest -t UDB5
pyProjectCreator.py -r ../.. -n LedTest -t AUAV3
=======================================
--- /trunk/build-all.bat Wed May 6 15:02:33 2015 UTC
+++ /trunk/build-all.bat Mon Jun 15 09:42:26 2015 UTC
@@ -1,11 +1,11 @@
@echo off
-mkdir build >nul 2>&1
-pushd build
+mkdir _build >nul 2>&1
+pushd _build
mkdir SIL >nul 2>&1
pushd SIL
-make -j 8 -f ../../makefile DEVICE=SIL
+make -j 8 -f ../../makefile DEVICE=SIL CONFIG=Cessna
popd
@rem mkdir PX4 >nul 2>&1
=======================================
--- /trunk/libSTM/syscalls.c Wed May 6 15:02:33 2015 UTC
+++ /trunk/libSTM/syscalls.c Mon Jun 15 09:42:26 2015 UTC
@@ -94,34 +94,6 @@
_kill(status, -1);
while (1) {}
}
-
-#if 0
-UART_HandleTypeDef UartHandle;
-
-void init_uart_stdio(unsigned long baud)
-{
- /*##-1- Configure the UART peripheral
######################################*/
- /* Put the USART peripheral in the Asynchronous mode (UART Mode) */
- /* UARTx configured as follow:
- - Word Length = 8 Bits
- - Stop Bit = One Stop bit
- - Parity = None
- - BaudRate = 9600 baud
- - Hardware flow control disabled (RTS and CTS signals) */
- UartHandle.Instance = UART2;
- UartHandle.Init.BaudRate = baud;
- UartHandle.Init.WordLength = UART_WORDLENGTH_8B;
- UartHandle.Init.StopBits = UART_STOPBITS_1;
- UartHandle.Init.Parity = UART_PARITY_NONE;
- UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
- UartHandle.Init.Mode = UART_MODE_TX_RX;
-
- if (HAL_UART_Init(&UartHandle) != HAL_OK)
- {
-// Error_Handler();
- }
-}
-#endif
int _write(int file, char *ptr, int len)
{
@@ -222,66 +194,3 @@
errno = ENOMEM;
return -1;
}
-
-
-//void _init(void)
-//{
-//}
-
-#if 0
-/**
- * @brief Update FIFO configuration
- * @param hpcd: PCD handle
- * @retval status
- */
-HAL_StatusTypeDef HAL_PCDEx_SetTxFiFo(PCD_HandleTypeDef *hpcd, uint8_t
fifo, uint16_t size)
-{
- uint8_t i = 0;
- uint32_t Tx_Offset = 0;
-
-
- /* TXn min size = 16 words. (n : Transmit FIFO index)
- * When a TxFIFO is not used, the Configuration should be as follows:
- * case 1 : n > m and Txn is not used (n,m : Transmit FIFO
indexes)
- * --> Txm can use the space allocated for Txn.
- * case2 : n < m and Txn is not used (n,m : Transmit FIFO
indexes)
- * --> Txn should be configured with the minimum space of 16 words
- * The FIFO is used optimally when used TxFIFOs are allocated in the top
- * of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as
IN ones.
- * When DMA is used 3n * FIFO locations should be reserved for internal
DMA registers */
-
- Tx_Offset = hpcd->Instance->GRXFSIZ;
-
- if(fifo == 0)
- {
- hpcd->Instance->DIEPTXF0_HNPTXFSIZ = (size << 16) | Tx_Offset;
- }
- else
- {
- Tx_Offset += (hpcd->Instance->DIEPTXF0_HNPTXFSIZ) >> 16;
- for (i = 0; i < (fifo - 1); i++)
- {
- Tx_Offset += (hpcd->Instance->DIEPTXF[i] >> 16);
- }
-
- /* Multiply Tx_Size by 2 to get higher performance */
- hpcd->Instance->DIEPTXF[fifo - 1] = (size << 16) | Tx_Offset;
-
- }
-
- return HAL_OK;
-}
-
-/**
- * @brief Update FIFO configuration
- * @param hpcd: PCD handle
- * @retval status
- */
-HAL_StatusTypeDef HAL_PCDEx_SetRxFiFo(PCD_HandleTypeDef *hpcd, uint16_t
size)
-{
-
- hpcd->Instance->GRXFSIZ = size;
-
- return HAL_OK;
-}
-#endif