23 changed files with 3029 additions and 6 deletions
@ -0,0 +1,41 @@
@@ -0,0 +1,41 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Board-specific startup code for the PX4FMUv2
|
||||
#
|
||||
|
||||
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
|
||||
LIBNAME = brd_px4fmuv2
|
||||
|
||||
include $(APPDIR)/mk/app.mk |
@ -0,0 +1,144 @@
@@ -0,0 +1,144 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_can.c |
||||
* |
||||
* Board-specific CAN functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#include <errno.h> |
||||
#include <debug.h> |
||||
|
||||
#include <nuttx/can.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
#include "chip.h" |
||||
#include "up_arch.h" |
||||
|
||||
#include "stm32.h" |
||||
#include "stm32_can.h" |
||||
#include "px4fmu_internal.h" |
||||
|
||||
#ifdef CONFIG_CAN |
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions |
||||
************************************************************************************/ |
||||
/* Configuration ********************************************************************/ |
||||
|
||||
#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) |
||||
# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1." |
||||
# undef CONFIG_STM32_CAN2 |
||||
#endif |
||||
|
||||
#ifdef CONFIG_STM32_CAN1 |
||||
# define CAN_PORT 1 |
||||
#else |
||||
# define CAN_PORT 2 |
||||
#endif |
||||
|
||||
/* Debug ***************************************************************************/ |
||||
/* Non-standard debug that may be enabled just for testing CAN */ |
||||
|
||||
#ifdef CONFIG_DEBUG_CAN |
||||
# define candbg dbg |
||||
# define canvdbg vdbg |
||||
# define canlldbg lldbg |
||||
# define canllvdbg llvdbg |
||||
#else |
||||
# define candbg(x...) |
||||
# define canvdbg(x...) |
||||
# define canlldbg(x...) |
||||
# define canllvdbg(x...) |
||||
#endif |
||||
|
||||
/************************************************************************************
|
||||
* Private Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: can_devinit |
||||
* |
||||
* Description: |
||||
* All STM32 architectures must provide the following interface to work with |
||||
* examples/can. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
int can_devinit(void) |
||||
{ |
||||
static bool initialized = false; |
||||
struct can_dev_s *can; |
||||
int ret; |
||||
|
||||
/* Check if we have already initialized */ |
||||
|
||||
if (!initialized) { |
||||
/* Call stm32_caninitialize() to get an instance of the CAN interface */ |
||||
|
||||
can = stm32_caninitialize(CAN_PORT); |
||||
|
||||
if (can == NULL) { |
||||
candbg("ERROR: Failed to get CAN interface\n"); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
/* Register the CAN driver at "/dev/can0" */ |
||||
|
||||
ret = can_register("/dev/can0", can); |
||||
|
||||
if (ret < 0) { |
||||
candbg("ERROR: can_register failed: %d\n", ret); |
||||
return ret; |
||||
} |
||||
|
||||
/* Now we are initialized */ |
||||
|
||||
initialized = true; |
||||
} |
||||
|
||||
return OK; |
||||
} |
||||
|
||||
#endif |
@ -0,0 +1,224 @@
@@ -0,0 +1,224 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_init.c |
||||
* |
||||
* PX4FMU-specific early startup code. This file implements the |
||||
* nsh_archinitialize() function that is called early by nsh during startup. |
||||
* |
||||
* Code here is run before the rcS script is invoked; it should start required |
||||
* subsystems and perform board-specific initialisation. |
||||
*/ |
||||
|
||||
/****************************************************************************
|
||||
* Included Files |
||||
****************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#include <stdbool.h> |
||||
#include <stdio.h> |
||||
#include <debug.h> |
||||
#include <errno.h> |
||||
|
||||
#include <nuttx/arch.h> |
||||
#include <nuttx/spi.h> |
||||
#include <nuttx/i2c.h> |
||||
#include <nuttx/mmcsd.h> |
||||
#include <nuttx/analog/adc.h> |
||||
|
||||
#include "stm32_internal.h" |
||||
#include "px4fmu_internal.h" |
||||
#include "stm32_uart.h" |
||||
|
||||
#include <arch/board/board.h> |
||||
|
||||
#include <drivers/drv_hrt.h> |
||||
#include <drivers/drv_led.h> |
||||
|
||||
#include <systemlib/cpuload.h> |
||||
|
||||
/****************************************************************************
|
||||
* Pre-Processor Definitions |
||||
****************************************************************************/ |
||||
|
||||
/* Configuration ************************************************************/ |
||||
|
||||
/* Debug ********************************************************************/ |
||||
|
||||
#ifdef CONFIG_CPP_HAVE_VARARGS |
||||
# ifdef CONFIG_DEBUG |
||||
# define message(...) lowsyslog(__VA_ARGS__) |
||||
# else |
||||
# define message(...) printf(__VA_ARGS__) |
||||
# endif |
||||
#else |
||||
# ifdef CONFIG_DEBUG |
||||
# define message lowsyslog |
||||
# else |
||||
# define message printf |
||||
# endif |
||||
#endif |
||||
|
||||
/****************************************************************************
|
||||
* Protected Functions |
||||
****************************************************************************/ |
||||
|
||||
/****************************************************************************
|
||||
* Public Functions |
||||
****************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize |
||||
* |
||||
* Description: |
||||
* All STM32 architectures must provide the following entry point. This entry point |
||||
* is called early in the intitialization -- after all memory has been configured |
||||
* and mapped but before any devices have been initialized. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_boardinitialize(void) |
||||
{ |
||||
/* configure SPI interfaces */ |
||||
stm32_spiinitialize(); |
||||
|
||||
/* configure LEDs */ |
||||
up_ledinit(); |
||||
} |
||||
|
||||
/****************************************************************************
|
||||
* Name: nsh_archinitialize |
||||
* |
||||
* Description: |
||||
* Perform architecture specific initialization |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
static struct spi_dev_s *spi1; |
||||
static struct spi_dev_s *spi2; |
||||
|
||||
#include <math.h> |
||||
|
||||
#ifdef __cplusplus |
||||
__EXPORT int matherr(struct __exception *e) |
||||
{ |
||||
return 1; |
||||
} |
||||
#else |
||||
__EXPORT int matherr(struct exception *e) |
||||
{ |
||||
return 1; |
||||
} |
||||
#endif |
||||
|
||||
__EXPORT int nsh_archinitialize(void) |
||||
{ |
||||
int result; |
||||
|
||||
/* configure the high-resolution time/callout interface */ |
||||
hrt_init(); |
||||
|
||||
/* configure CPU load estimation */ |
||||
#ifdef CONFIG_SCHED_INSTRUMENTATION |
||||
cpuload_initialize_once(); |
||||
#endif |
||||
|
||||
/* set up the serial DMA polling */ |
||||
static struct hrt_call serial_dma_call; |
||||
struct timespec ts; |
||||
|
||||
/*
|
||||
* Poll at 1ms intervals for received bytes that have not triggered |
||||
* a DMA event. |
||||
*/ |
||||
ts.tv_sec = 0; |
||||
ts.tv_nsec = 1000000; |
||||
|
||||
hrt_call_every(&serial_dma_call, |
||||
ts_to_abstime(&ts), |
||||
ts_to_abstime(&ts), |
||||
(hrt_callout)stm32_serial_dma_poll, |
||||
NULL); |
||||
|
||||
// initial LED state
|
||||
// XXX need to make this work again
|
||||
// drv_led_start();
|
||||
up_ledoff(LED_AMBER); |
||||
|
||||
/* Configure SPI-based devices */ |
||||
|
||||
spi1 = up_spiinitialize(1); |
||||
|
||||
if (!spi1) { |
||||
message("[boot] FAILED to initialize SPI port 1\r\n"); |
||||
up_ledon(LED_AMBER); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
// Default SPI1 to 1MHz and de-assert the known chip selects.
|
||||
SPI_SETFREQUENCY(spi1, 10000000); |
||||
SPI_SETBITS(spi1, 8); |
||||
SPI_SETMODE(spi1, SPIDEV_MODE3); |
||||
SPI_SELECT(spi1, PX4_SPIDEV_GYRO, false); |
||||
SPI_SELECT(spi1, PX4_SPIDEV_ACCEL_MAG, false); |
||||
SPI_SELECT(spi1, PX4_SPIDEV_BARO, false); |
||||
up_udelay(20); |
||||
|
||||
message("[boot] Successfully initialized SPI port 1\r\n"); |
||||
|
||||
/* Get the SPI port for the FRAM */ |
||||
|
||||
message("[boot] Initializing SPI port 2\n"); |
||||
spi2 = up_spiinitialize(3); |
||||
|
||||
if (!spi2) { |
||||
message("[boot] FAILED to initialize SPI port 2\n"); |
||||
up_ledon(LED_AMBER); |
||||
return -ENODEV; |
||||
} |
||||
|
||||
message("[boot] Successfully initialized SPI port 2\n"); |
||||
|
||||
/* XXX need a driver to bind the FRAM to */ |
||||
|
||||
//message("[boot] Successfully bound SPI port 2 to the FRAM driver\n");
|
||||
|
||||
/* configure ADC pins */ |
||||
stm32_configgpio(GPIO_ADC1_IN10); |
||||
stm32_configgpio(GPIO_ADC1_IN11); |
||||
stm32_configgpio(GPIO_ADC1_IN12); |
||||
|
||||
return OK; |
||||
} |
@ -0,0 +1,106 @@
@@ -0,0 +1,106 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_internal.h |
||||
* |
||||
* PX4FMU internal definitions |
||||
*/ |
||||
|
||||
#pragma once |
||||
|
||||
/****************************************************************************************************
|
||||
* Included Files |
||||
****************************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#include <nuttx/compiler.h> |
||||
#include <stdint.h> |
||||
|
||||
__BEGIN_DECLS |
||||
|
||||
/* these headers are not C++ safe */ |
||||
#include <stm32_internal.h> |
||||
|
||||
|
||||
/****************************************************************************************************
|
||||
* Definitions |
||||
****************************************************************************************************/ |
||||
/* Configuration ************************************************************************************/ |
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/ |
||||
/* LEDs */ |
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTE|GPIO_PIN12) |
||||
|
||||
/* External interrupts */ |
||||
|
||||
/* SPI chip selects */ |
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) |
||||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) |
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7) |
||||
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10) |
||||
|
||||
/* USB OTG FS
|
||||
* |
||||
* PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED) |
||||
*/ |
||||
#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9) |
||||
|
||||
/****************************************************************************************************
|
||||
* Public Types |
||||
****************************************************************************************************/ |
||||
|
||||
/****************************************************************************************************
|
||||
* Public data |
||||
****************************************************************************************************/ |
||||
|
||||
#ifndef __ASSEMBLY__ |
||||
|
||||
/****************************************************************************************************
|
||||
* Public Functions |
||||
****************************************************************************************************/ |
||||
|
||||
/****************************************************************************************************
|
||||
* Name: stm32_spiinitialize |
||||
* |
||||
* Description: |
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board. |
||||
* |
||||
****************************************************************************************************/ |
||||
|
||||
extern void stm32_spiinitialize(void); |
||||
|
||||
#endif /* __ASSEMBLY__ */ |
||||
|
||||
__END_DECLS |
@ -0,0 +1,105 @@
@@ -0,0 +1,105 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/*
|
||||
* @file px4fmu_pwm_servo.c |
||||
* |
||||
* Configuration data for the stm32 pwm_servo driver. |
||||
* |
||||
* Note that these arrays must always be fully-sized. |
||||
*/ |
||||
|
||||
#include <stdint.h> |
||||
|
||||
#include <drivers/stm32/drv_pwm_servo.h> |
||||
|
||||
#include <arch/board/board.h> |
||||
#include <drivers/drv_pwm_output.h> |
||||
|
||||
#include <stm32_internal.h> |
||||
#include <stm32_gpio.h> |
||||
#include <stm32_tim.h> |
||||
|
||||
__EXPORT const struct pwm_servo_timer pwm_timers[PWM_SERVO_MAX_TIMERS] = { |
||||
{ |
||||
.base = STM32_TIM1_BASE, |
||||
.clock_register = STM32_RCC_APB1ENR, |
||||
.clock_bit = RCC_APB2ENR_TIM1EN, |
||||
.clock_freq = STM32_APB2_TIM1_CLKIN |
||||
}, |
||||
{ |
||||
.base = STM32_TIM4_BASE, |
||||
.clock_register = STM32_RCC_APB1ENR, |
||||
.clock_bit = RCC_APB1ENR_TIM4EN, |
||||
.clock_freq = STM32_APB1_TIM4_CLKIN |
||||
} |
||||
}; |
||||
|
||||
__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = { |
||||
{ |
||||
.gpio = GPIO_TIM1_CH4OUT, |
||||
.timer_index = 0, |
||||
.timer_channel = 4, |
||||
.default_value = 1000, |
||||
}, |
||||
{ |
||||
.gpio = GPIO_TIM1_CH3OUT, |
||||
.timer_index = 0, |
||||
.timer_channel = 3, |
||||
.default_value = 1000, |
||||
}, |
||||
{ |
||||
.gpio = GPIO_TIM1_CH2OUT, |
||||
.timer_index = 0, |
||||
.timer_channel = 2, |
||||
.default_value = 1000, |
||||
}, |
||||
{ |
||||
.gpio = GPIO_TIM1_CH1OUT, |
||||
.timer_index = 0, |
||||
.timer_channel = 1, |
||||
.default_value = 1000, |
||||
}, |
||||
{ |
||||
.gpio = GPIO_TIM4_CH2OUT, |
||||
.timer_index = 1, |
||||
.timer_channel = 2, |
||||
.default_value = 1000, |
||||
}, |
||||
{ |
||||
.gpio = GPIO_TIM4_CH3OUT, |
||||
.timer_index = 1, |
||||
.timer_channel = 3, |
||||
.default_value = 1000, |
||||
} |
||||
}; |
@ -0,0 +1,141 @@
@@ -0,0 +1,141 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_spi.c |
||||
* |
||||
* Board-specific SPI functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <debug.h> |
||||
|
||||
#include <nuttx/spi.h> |
||||
#include <arch/board/board.h> |
||||
|
||||
#include "up_arch.h" |
||||
#include "chip.h" |
||||
#include "stm32_internal.h" |
||||
#include "px4fmu_internal.h" |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_spiinitialize |
||||
* |
||||
* Description: |
||||
* Called to configure SPI chip select GPIO pins for the PX4FMU board. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void weak_function stm32_spiinitialize(void) |
||||
{ |
||||
#ifdef CONFIG_STM32_SPI1 |
||||
stm32_configgpio(GPIO_SPI_CS_GYRO); |
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG); |
||||
stm32_configgpio(GPIO_SPI_CS_BARO); |
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral |
||||
* state machines |
||||
*/ |
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1); |
||||
#endif |
||||
|
||||
#ifdef CONFIG_STM32_SPI2 |
||||
stm32_configgpio(GPIO_SPI_CS_FRAM); |
||||
stm32_gpiowrite(GPIO_SPI_CS_FRAM, 1); |
||||
#endif |
||||
} |
||||
|
||||
__EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) |
||||
{ |
||||
/* SPI select is active low, so write !selected to select the device */ |
||||
|
||||
switch (devid) { |
||||
case PX4_SPIDEV_GYRO: |
||||
/* Making sure the other peripherals are not selected */ |
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected); |
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1); |
||||
break; |
||||
|
||||
case PX4_SPIDEV_ACCEL_MAG: |
||||
/* Making sure the other peripherals are not selected */ |
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected); |
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1); |
||||
break; |
||||
|
||||
case PX4_SPIDEV_BARO: |
||||
/* Making sure the other peripherals are not selected */ |
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1); |
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected); |
||||
break; |
||||
|
||||
default: |
||||
break; |
||||
} |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) |
||||
{ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2 |
||||
__EXPORT void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) |
||||
{ |
||||
/* there can only be one device on this bus, so always select it */ |
||||
stm32_gpiowrite(GPIO_SPI_CS_FRAM, !selected); |
||||
} |
||||
|
||||
__EXPORT uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) |
||||
{ |
||||
/* FRAM is always present */ |
||||
return SPI_STATUS_PRESENT; |
||||
} |
||||
#endif |
@ -0,0 +1,108 @@
@@ -0,0 +1,108 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* @file px4fmu_usb.c |
||||
* |
||||
* Board-specific USB functions. |
||||
*/ |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
|
||||
#include <sys/types.h> |
||||
#include <stdint.h> |
||||
#include <stdbool.h> |
||||
#include <debug.h> |
||||
|
||||
#include <nuttx/usb/usbdev.h> |
||||
#include <nuttx/usb/usbdev_trace.h> |
||||
|
||||
#include "up_arch.h" |
||||
#include "stm32_internal.h" |
||||
#include "px4fmu_internal.h" |
||||
|
||||
/************************************************************************************
|
||||
* Definitions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Private Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Public Functions |
||||
************************************************************************************/ |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbinitialize |
||||
* |
||||
* Description: |
||||
* Called to setup USB-related GPIO pins for the PX4FMU board. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_usbinitialize(void) |
||||
{ |
||||
/* The OTG FS has an internal soft pull-up */ |
||||
|
||||
/* Configure the OTG FS VBUS sensing GPIO, Power On, and Overcurrent GPIOs */ |
||||
|
||||
#ifdef CONFIG_STM32_OTGFS |
||||
stm32_configgpio(GPIO_OTGFS_VBUS); |
||||
/* XXX We only support device mode
|
||||
stm32_configgpio(GPIO_OTGFS_PWRON); |
||||
stm32_configgpio(GPIO_OTGFS_OVER); |
||||
*/ |
||||
#endif |
||||
} |
||||
|
||||
/************************************************************************************
|
||||
* Name: stm32_usbsuspend |
||||
* |
||||
* Description: |
||||
* Board logic must provide the stm32_usbsuspend logic if the USBDEV driver is |
||||
* used. This function is called whenever the USB enters or leaves suspend mode. |
||||
* This is an opportunity for the board logic to shutdown clocks, power, etc. |
||||
* while the USB is suspended. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
__EXPORT void stm32_usbsuspend(FAR struct usbdev_s *dev, bool resume) |
||||
{ |
||||
ulldbg("resume: %d\n", resume); |
||||
} |
||||
|
@ -0,0 +1,62 @@
@@ -0,0 +1,62 @@
|
||||
#
|
||||
# Makefile for the px4fmu_default configuration
|
||||
#
|
||||
|
||||
#
|
||||
# Use the configuration's ROMFS.
|
||||
#
|
||||
ROMFS_ROOT = $(PX4_BASE)/ROMFS/$(CONFIG)
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
# In general, these should move to modules over time.
|
||||
#
|
||||
# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
|
||||
# to make the table a bit more readable.
|
||||
#
|
||||
define _B |
||||
$(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
|
||||
endef |
||||
|
||||
# command priority stack entrypoint
|
||||
BUILTIN_COMMANDS := \
|
||||
$(call _B, adc, , 2048, adc_main ) \
|
||||
$(call _B, ardrone_interface, SCHED_PRIORITY_MAX-15, 2048, ardrone_interface_main ) \
|
||||
$(call _B, attitude_estimator_ekf, , 2048, attitude_estimator_ekf_main) \
|
||||
$(call _B, bl_update, , 4096, bl_update_main ) \
|
||||
$(call _B, blinkm, , 2048, blinkm_main ) \
|
||||
$(call _B, boardinfo, , 2048, boardinfo_main ) \
|
||||
$(call _B, commander, SCHED_PRIORITY_MAX-30, 2048, commander_main ) \
|
||||
$(call _B, control_demo, , 2048, control_demo_main ) \
|
||||
$(call _B, delay_test, , 2048, delay_test_main ) \
|
||||
$(call _B, eeprom, , 4096, eeprom_main ) \
|
||||
$(call _B, fixedwing_att_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_att_control_main ) \
|
||||
$(call _B, fixedwing_pos_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_pos_control_main ) \
|
||||
$(call _B, fmu, , 2048, fmu_main ) \
|
||||
$(call _B, gps, , 2048, gps_main ) \
|
||||
$(call _B, hil, , 2048, hil_main ) \
|
||||
$(call _B, hott_telemetry, , 2048, hott_telemetry_main ) \
|
||||
$(call _B, kalman_demo, SCHED_PRIORITY_MAX-30, 2048, kalman_demo_main ) \
|
||||
$(call _B, l3gd20, , 2048, l3gd20_main ) \
|
||||
$(call _B, math_demo, , 8192, math_demo_main ) \
|
||||
$(call _B, mavlink, , 2048, mavlink_main ) \
|
||||
$(call _B, mavlink_onboard, , 2048, mavlink_onboard_main ) \
|
||||
$(call _B, mixer, , 4096, mixer_main ) \
|
||||
$(call _B, ms5611, , 2048, ms5611_main ) \
|
||||
$(call _B, multirotor_att_control, SCHED_PRIORITY_MAX-15, 2048, multirotor_att_control_main) \
|
||||
$(call _B, multirotor_pos_control, SCHED_PRIORITY_MAX-25, 2048, multirotor_pos_control_main) \
|
||||
$(call _B, param, , 4096, param_main ) \
|
||||
$(call _B, perf, , 2048, perf_main ) \
|
||||
$(call _B, position_estimator, , 4096, position_estimator_main ) \
|
||||
$(call _B, preflight_check, , 2048, preflight_check_main ) \
|
||||
$(call _B, px4io, , 2048, px4io_main ) \
|
||||
$(call _B, reboot, , 2048, reboot_main ) \
|
||||
$(call _B, sdlog, SCHED_PRIORITY_MAX-30, 2048, sdlog_main ) \
|
||||
$(call _B, sensors, SCHED_PRIORITY_MAX-5, 4096, sensors_main ) \
|
||||
$(call _B, sercon, , 2048, sercon_main ) \
|
||||
$(call _B, serdis, , 2048, serdis_main ) \
|
||||
$(call _B, tests, , 12000, tests_main ) \
|
||||
$(call _B, tone_alarm, , 2048, tone_alarm_main ) \
|
||||
$(call _B, top, SCHED_PRIORITY_DEFAULT-10, 3000, top_main ) \
|
||||
$(call _B, uorb, , 4096, uorb_main )
|
@ -0,0 +1,7 @@
@@ -0,0 +1,7 @@
|
||||
# |
||||
# For a description of the syntax of this configuration file, |
||||
# see misc/tools/kconfig-language.txt. |
||||
# |
||||
|
||||
if ARCH_BOARD_PX4FMUV2 |
||||
endif |
@ -0,0 +1,184 @@
@@ -0,0 +1,184 @@
|
||||
############################################################################ |
||||
# configs/px4fmu/common/Make.defs |
||||
# |
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved. |
||||
# Author: Gregory Nutt <gnutt@nuttx.org> |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name NuttX nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
# |
||||
# Generic Make.defs for the PX4FMUV2 |
||||
# Do not specify/use this file directly - it is included by config-specific |
||||
# Make.defs in the per-config directories. |
||||
# |
||||
|
||||
include ${TOPDIR}/tools/Config.mk |
||||
|
||||
# |
||||
# We only support building with the ARM bare-metal toolchain from |
||||
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS. |
||||
# |
||||
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI |
||||
|
||||
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs |
||||
|
||||
CC = $(CROSSDEV)gcc |
||||
CXX = $(CROSSDEV)g++ |
||||
CPP = $(CROSSDEV)gcc -E |
||||
LD = $(CROSSDEV)ld |
||||
AR = $(CROSSDEV)ar rcs |
||||
NM = $(CROSSDEV)nm |
||||
OBJCOPY = $(CROSSDEV)objcopy |
||||
OBJDUMP = $(CROSSDEV)objdump |
||||
|
||||
MAXOPTIMIZATION = -O3 |
||||
ARCHCPUFLAGS = -mcpu=cortex-m4 \ |
||||
-mthumb \ |
||||
-march=armv7e-m \ |
||||
-mfpu=fpv4-sp-d16 \ |
||||
-mfloat-abi=hard |
||||
|
||||
|
||||
# enable precise stack overflow tracking |
||||
INSTRUMENTATIONDEFINES = -finstrument-functions \ |
||||
-ffixed-r10 |
||||
|
||||
# pull in *just* libm from the toolchain ... this is grody |
||||
LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}" |
||||
EXTRA_LIBS += $(LIBM) |
||||
|
||||
# use our linker script |
||||
LDSCRIPT = ld.script |
||||
|
||||
ifeq ($(WINTOOL),y) |
||||
# Windows-native toolchains |
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh |
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh |
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh |
||||
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" |
||||
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}" |
||||
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT)}" |
||||
else |
||||
ifeq ($(PX4_WINTOOL),y) |
||||
# Windows-native toolchains (MSYS) |
||||
DIRLINK = $(TOPDIR)/tools/copydir.sh |
||||
DIRUNLINK = $(TOPDIR)/tools/unlink.sh |
||||
MKDEP = $(TOPDIR)/tools/mknulldeps.sh |
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include |
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx |
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) |
||||
else |
||||
# Linux/Cygwin-native toolchain |
||||
MKDEP = $(TOPDIR)/tools/mkdeps.sh |
||||
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include |
||||
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx |
||||
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/common/$(LDSCRIPT) |
||||
endif |
||||
endif |
||||
|
||||
# tool versions |
||||
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'} |
||||
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1} |
||||
|
||||
# optimisation flags |
||||
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ |
||||
-fno-strict-aliasing \ |
||||
-fno-strength-reduce \ |
||||
-fomit-frame-pointer \ |
||||
-funsafe-math-optimizations \ |
||||
-fno-builtin-printf \ |
||||
-ffunction-sections \ |
||||
-fdata-sections |
||||
|
||||
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y") |
||||
ARCHOPTIMIZATION += -g |
||||
endif |
||||
|
||||
ARCHCFLAGS = -std=gnu99 |
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x |
||||
ARCHWARNINGS = -Wall \ |
||||
-Wextra \ |
||||
-Wdouble-promotion \ |
||||
-Wshadow \ |
||||
-Wfloat-equal \ |
||||
-Wframe-larger-than=1024 \ |
||||
-Wpointer-arith \ |
||||
-Wlogical-op \ |
||||
-Wmissing-declarations \ |
||||
-Wpacked \ |
||||
-Wno-unused-parameter |
||||
# -Wcast-qual - generates spurious noreturn attribute warnings, try again later |
||||
# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code |
||||
# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives |
||||
|
||||
ARCHCWARNINGS = $(ARCHWARNINGS) \ |
||||
-Wbad-function-cast \ |
||||
-Wstrict-prototypes \ |
||||
-Wold-style-declaration \ |
||||
-Wmissing-parameter-type \ |
||||
-Wmissing-prototypes \ |
||||
-Wnested-externs \ |
||||
-Wunsuffixed-float-constants |
||||
ARCHWARNINGSXX = $(ARCHWARNINGS) \ |
||||
-Wno-psabi |
||||
ARCHDEFINES = |
||||
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 |
||||
|
||||
# this seems to be the only way to add linker flags |
||||
EXTRA_LIBS += --warn-common \ |
||||
--gc-sections |
||||
|
||||
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common |
||||
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) |
||||
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe |
||||
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) |
||||
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) |
||||
AFLAGS = $(CFLAGS) -D__ASSEMBLY__ |
||||
|
||||
NXFLATLDFLAGS1 = -r -d -warn-common |
||||
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections |
||||
LDNXFLATFLAGS = -e main -s 2048 |
||||
|
||||
OBJEXT = .o |
||||
LIBEXT = .a |
||||
EXEEXT = |
||||
|
||||
|
||||
# produce partially-linked $1 from files in $2 |
||||
define PRELINK |
||||
@echo "PRELINK: $1" |
||||
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1 |
||||
endef |
||||
|
||||
HOSTCC = gcc |
||||
HOSTINCLUDES = -I. |
||||
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe |
||||
HOSTLDFLAGS = |
||||
|
@ -0,0 +1,150 @@
@@ -0,0 +1,150 @@
|
||||
/**************************************************************************** |
||||
* configs/px4fmu/common/ld.script |
||||
* |
||||
* Copyright (C) 2011 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name NuttX nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/* The STM32F427 has 2048Kb of FLASH beginning at address 0x0800:0000 and |
||||
* 256Kb of SRAM. SRAM is split up into three blocks: |
||||
* |
||||
* 1) 112Kb of SRAM beginning at address 0x2000:0000 |
||||
* 2) 16Kb of SRAM beginning at address 0x2001:c000 |
||||
* 3) 64Kb of SRAM beginning at address 0x2002:0000 |
||||
* 4) 64Kb of TCM SRAM beginning at address 0x1000:0000 |
||||
* |
||||
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000 |
||||
* where the code expects to begin execution by jumping to the entry point in |
||||
* the 0x0800:0000 address range. |
||||
* |
||||
* The first 0x4000 of flash is reserved for the bootloader. |
||||
*/ |
||||
|
||||
MEMORY |
||||
{ |
||||
flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K |
||||
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K |
||||
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K |
||||
} |
||||
|
||||
OUTPUT_ARCH(arm) |
||||
|
||||
ENTRY(__start) /* treat __start as the anchor for dead code stripping */ |
||||
EXTERN(_vectors) /* force the vectors to be included in the output */ |
||||
|
||||
/* |
||||
* Ensure that abort() is present in the final object. The exception handling |
||||
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided). |
||||
*/ |
||||
EXTERN(abort) |
||||
|
||||
SECTIONS |
||||
{ |
||||
.text : { |
||||
_stext = ABSOLUTE(.); |
||||
*(.vectors) |
||||
*(.text .text.*) |
||||
*(.fixup) |
||||
*(.gnu.warning) |
||||
*(.rodata .rodata.*) |
||||
*(.gnu.linkonce.t.*) |
||||
*(.got) |
||||
*(.gcc_except_table) |
||||
*(.gnu.linkonce.r.*) |
||||
_etext = ABSOLUTE(.); |
||||
|
||||
/* |
||||
* This is a hack to make the newlib libm __errno() call |
||||
* use the NuttX get_errno_ptr() function. |
||||
*/ |
||||
__errno = get_errno_ptr; |
||||
} > flash |
||||
|
||||
/* |
||||
* Init functions (static constructors and the like) |
||||
*/ |
||||
.init_section : { |
||||
_sinit = ABSOLUTE(.); |
||||
KEEP(*(.init_array .init_array.*)) |
||||
_einit = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
/* |
||||
* Construction data for parameters. |
||||
*/ |
||||
__param ALIGN(4): { |
||||
__param_start = ABSOLUTE(.); |
||||
KEEP(*(__param*)) |
||||
__param_end = ABSOLUTE(.); |
||||
} > flash |
||||
|
||||
.ARM.extab : { |
||||
*(.ARM.extab*) |
||||
} > flash |
||||
|
||||
__exidx_start = ABSOLUTE(.); |
||||
.ARM.exidx : { |
||||
*(.ARM.exidx*) |
||||
} > flash |
||||
__exidx_end = ABSOLUTE(.); |
||||
|
||||
_eronly = ABSOLUTE(.); |
||||
|
||||
.data : { |
||||
_sdata = ABSOLUTE(.); |
||||
*(.data .data.*) |
||||
*(.gnu.linkonce.d.*) |
||||
CONSTRUCTORS |
||||
_edata = ABSOLUTE(.); |
||||
} > sram AT > flash |
||||
|
||||
.bss : { |
||||
_sbss = ABSOLUTE(.); |
||||
*(.bss .bss.*) |
||||
*(.gnu.linkonce.b.*) |
||||
*(COMMON) |
||||
_ebss = ABSOLUTE(.); |
||||
} > sram |
||||
|
||||
/* Stabs debugging sections. */ |
||||
.stab 0 : { *(.stab) } |
||||
.stabstr 0 : { *(.stabstr) } |
||||
.stab.excl 0 : { *(.stab.excl) } |
||||
.stab.exclstr 0 : { *(.stab.exclstr) } |
||||
.stab.index 0 : { *(.stab.index) } |
||||
.stab.indexstr 0 : { *(.stab.indexstr) } |
||||
.comment 0 : { *(.comment) } |
||||
.debug_abbrev 0 : { *(.debug_abbrev) } |
||||
.debug_info 0 : { *(.debug_info) } |
||||
.debug_line 0 : { *(.debug_line) } |
||||
.debug_pubnames 0 : { *(.debug_pubnames) } |
||||
.debug_aranges 0 : { *(.debug_aranges) } |
||||
} |
@ -0,0 +1,351 @@
@@ -0,0 +1,351 @@
|
||||
/************************************************************************************
|
||||
* configs/px4fmu/include/board.h |
||||
* include/arch/board/board.h |
||||
* |
||||
* Copyright (C) 2009 Gregory Nutt. All rights reserved. |
||||
* Author: Gregory Nutt <gnutt@nuttx.org> |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name NuttX nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
#ifndef __ARCH_BOARD_BOARD_H |
||||
#define __ARCH_BOARD_BOARD_H |
||||
|
||||
/************************************************************************************
|
||||
* Included Files |
||||
************************************************************************************/ |
||||
|
||||
#include <nuttx/config.h> |
||||
#ifndef __ASSEMBLY__ |
||||
# include <stdint.h> |
||||
#endif |
||||
|
||||
/************************************************************************************
|
||||
* Definitions |
||||
************************************************************************************/ |
||||
|
||||
/* Clocking *************************************************************************/ |
||||
/* The PX4FMUV2 uses a 24MHz crystal connected to the HSE.
|
||||
* |
||||
* This is the "standard" configuration as set up by arch/arm/src/stm32f40xx_rcc.c: |
||||
* System Clock source : PLL (HSE) |
||||
* SYSCLK(Hz) : 168000000 Determined by PLL configuration |
||||
* HCLK(Hz) : 168000000 (STM32_RCC_CFGR_HPRE) |
||||
* AHB Prescaler : 1 (STM32_RCC_CFGR_HPRE) |
||||
* APB1 Prescaler : 4 (STM32_RCC_CFGR_PPRE1) |
||||
* APB2 Prescaler : 2 (STM32_RCC_CFGR_PPRE2) |
||||
* HSE Frequency(Hz) : 24000000 (STM32_BOARD_XTAL) |
||||
* PLLM : 24 (STM32_PLLCFG_PLLM) |
||||
* PLLN : 336 (STM32_PLLCFG_PLLN) |
||||
* PLLP : 2 (STM32_PLLCFG_PLLP) |
||||
* PLLQ : 7 (STM32_PLLCFG_PPQ) |
||||
* Main regulator output voltage : Scale1 mode Needed for high speed SYSCLK |
||||
* Flash Latency(WS) : 5 |
||||
* Prefetch Buffer : OFF |
||||
* Instruction cache : ON |
||||
* Data cache : ON |
||||
* Require 48MHz for USB OTG FS, : Enabled |
||||
* SDIO and RNG clock |
||||
*/ |
||||
|
||||
/* HSI - 16 MHz RC factory-trimmed
|
||||
* LSI - 32 KHz RC |
||||
* HSE - On-board crystal frequency is 24MHz |
||||
* LSE - not installed |
||||
*/ |
||||
|
||||
#define STM32_BOARD_XTAL 24000000ul |
||||
|
||||
#define STM32_HSI_FREQUENCY 16000000ul |
||||
#define STM32_LSI_FREQUENCY 32000 |
||||
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL |
||||
//#define STM32_LSE_FREQUENCY 32768
|
||||
|
||||
/* Main PLL Configuration.
|
||||
* |
||||
* PLL source is HSE |
||||
* PLL_VCO = (STM32_HSE_FREQUENCY / PLLM) * PLLN |
||||
* = (25,000,000 / 25) * 336 |
||||
* = 336,000,000 |
||||
* SYSCLK = PLL_VCO / PLLP |
||||
* = 336,000,000 / 2 = 168,000,000 |
||||
* USB OTG FS, SDIO and RNG Clock |
||||
* = PLL_VCO / PLLQ |
||||
* = 48,000,000 |
||||
*/ |
||||
|
||||
#define STM32_PLLCFG_PLLM RCC_PLLCFG_PLLM(24) |
||||
#define STM32_PLLCFG_PLLN RCC_PLLCFG_PLLN(336) |
||||
#define STM32_PLLCFG_PLLP RCC_PLLCFG_PLLP_2 |
||||
#define STM32_PLLCFG_PLLQ RCC_PLLCFG_PLLQ(7) |
||||
|
||||
#define STM32_SYSCLK_FREQUENCY 168000000ul |
||||
|
||||
/* AHB clock (HCLK) is SYSCLK (168MHz) */ |
||||
|
||||
#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK /* HCLK = SYSCLK / 1 */ |
||||
#define STM32_HCLK_FREQUENCY STM32_SYSCLK_FREQUENCY |
||||
#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */ |
||||
|
||||
/* APB1 clock (PCLK1) is HCLK/4 (42MHz) */ |
||||
|
||||
#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd4 /* PCLK1 = HCLK / 4 */ |
||||
#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/4) |
||||
|
||||
/* Timers driven from APB1 will be twice PCLK1 */ |
||||
|
||||
#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM12_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM13_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB1_TIM14_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
|
||||
/* APB2 clock (PCLK2) is HCLK/2 (84MHz) */ |
||||
|
||||
#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLKd2 /* PCLK2 = HCLK / 2 */ |
||||
#define STM32_PCLK2_FREQUENCY (STM32_HCLK_FREQUENCY/2) |
||||
|
||||
/* Timers driven from APB2 will be twice PCLK2 */ |
||||
|
||||
#define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY) |
||||
|
||||
/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
|
||||
* otherwise frequency is 2xAPBx.
|
||||
* Note: TIM1,8 are on APB2, others on APB1 |
||||
*/ |
||||
|
||||
#define STM32_TIM18_FREQUENCY (2*STM32_PCLK2_FREQUENCY) |
||||
#define STM32_TIM27_FREQUENCY (2*STM32_PCLK1_FREQUENCY) |
||||
|
||||
/* SDIO dividers. Note that slower clocking is required when DMA is disabled
|
||||
* in order to avoid RX overrun/TX underrun errors due to delayed responses |
||||
* to service FIFOs in interrupt driven mode. These values have not been |
||||
* tuned!!! |
||||
* |
||||
* HCLK=72MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(178+2)=400 KHz |
||||
*/ |
||||
|
||||
#define SDIO_INIT_CLKDIV (178 << SDIO_CLKCR_CLKDIV_SHIFT) |
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(2+2)=18 MHz
|
||||
* DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz |
||||
*/ |
||||
|
||||
#ifdef CONFIG_SDIO_DMA |
||||
# define SDIO_MMCXFR_CLKDIV (2 << SDIO_CLKCR_CLKDIV_SHIFT) |
||||
#else |
||||
# define SDIO_MMCXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) |
||||
#endif |
||||
|
||||
/* DMA ON: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(1+2)=24 MHz
|
||||
* DMA OFF: HCLK=72 MHz, SDIOCLK=72MHz, SDIO_CK=HCLK/(3+2)=14.4 MHz |
||||
*/ |
||||
|
||||
#ifdef CONFIG_SDIO_DMA |
||||
# define SDIO_SDXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT) |
||||
#else |
||||
# define SDIO_SDXFR_CLKDIV (3 << SDIO_CLKCR_CLKDIV_SHIFT) |
||||
#endif |
||||
|
||||
/* High-resolution timer
|
||||
*/ |
||||
#ifdef CONFIG_HRT_TIMER |
||||
# define HRT_TIMER 8 /* use timer8 for the HRT */ |
||||
# define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */ |
||||
#endif |
||||
|
||||
/* Alternate function pin selections ************************************************/ |
||||
|
||||
/*
|
||||
* UARTs. |
||||
*/ |
||||
#define GPIO_USART1_RX GPIO_USART1_RX_1 /* console in from IO */ |
||||
#define GPIO_USART1_TX 0 /* USART1 is RX-only */ |
||||
|
||||
#define GPIO_USART2_RX GPIO_USART2_RX_2 |
||||
#define GPIO_USART2_TX GPIO_USART2_TX_2 |
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 |
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 |
||||
|
||||
#define GPIO_USART3_RX GPIO_USART3_RX_3 |
||||
#define GPIO_USART3_TX GPIO_USART3_TX_3 |
||||
#define GPIO_USART2_RTS GPIO_USART2_RTS_2 |
||||
#define GPIO_USART2_CTS GPIO_USART2_CTS_2 |
||||
|
||||
#define GPIO_UART4_RX GPIO_UART4_RX_1 |
||||
#define GPIO_UART4_TX GPIO_UART4_TX_1 |
||||
|
||||
#define GPIO_USART6_RX GPIO_USART6_RX_1 |
||||
#define GPIO_USART6_TX GPIO_USART6_TX_1 |
||||
|
||||
#define GPIO_UART7_RX GPIO_UART7_RX_1 |
||||
#define GPIO_UART7_TX GPIO_UART7_TX_1 |
||||
|
||||
/* UART8 has no alternate pin config */ |
||||
|
||||
/* UART RX DMA configurations */ |
||||
#define DMAMAP_USART1_RX DMAMAP_USART1_RX_2 |
||||
#define DMAMAP_USART6_RX DMAMAP_USART6_RX_2 |
||||
|
||||
/*
|
||||
* PWM |
||||
* |
||||
* Six PWM outputs are configured. |
||||
* |
||||
* Pins: |
||||
* |
||||
* CH1 : PE14 : TIM1_CH4 |
||||
* CH2 : PE13 : TIM1_CH3 |
||||
* CH3 : PE11 : TIM1_CH2 |
||||
* CH4 : PE9 : TIM1_CH1 |
||||
* CH5 : PD13 : TIM4_CH2 |
||||
* CH6 : PD14 : TIM4_CH3 |
||||
* |
||||
*/ |
||||
#define GPIO_TIM1_CH1OUT GPIO_TIM1_CH1OUT_2 |
||||
#define GPIO_TIM1_CH2OUT GPIO_TIM1_CH2OUT_2 |
||||
#define GPIO_TIM1_CH3OUT GPIO_TIM1_CH3OUT_2 |
||||
#define GPIO_TIM1_CH4OUT GPIO_TIM1_CH4OUT_2 |
||||
#define GPIO_TIM4_CH2OUT GPIO_TIM4_CH2OUT_2 |
||||
#define GPIO_TIM4_CH3OUT GPIO_TIM4_CH3OUT_2 |
||||
|
||||
/*
|
||||
* CAN |
||||
* |
||||
* CAN1 is routed to the onboard transceiver.
|
||||
* CAN2 is routed to the expansion connector. |
||||
*/ |
||||
|
||||
#define GPIO_CAN1_RX GPIO_CAN1_RX_3 |
||||
#define GPIO_CAN1_TX GPIO_CAN1_TX_3 |
||||
#define GPIO_CAN2_RX GPIO_CAN2_RX_1 |
||||
#define GPIO_CAN2_TX GPIO_CAN2_TX_2 |
||||
|
||||
/*
|
||||
* I2C |
||||
* |
||||
* The optional _GPIO configurations allow the I2C driver to manually |
||||
* reset the bus to clear stuck slaves. They match the pin configuration, |
||||
* but are normally-high GPIOs. |
||||
*/ |
||||
#define GPIO_I2C1_SCL GPIO_I2C1_SCL_2 |
||||
#define GPIO_I2C1_SDA GPIO_I2C1_SDA_2 |
||||
#define GPIO_I2C1_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN8) |
||||
#define GPIO_I2C1_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN9) |
||||
|
||||
#define GPIO_I2C2_SCL GPIO_I2C2_SCL_1 |
||||
#define GPIO_I2C2_SDA GPIO_I2C2_SDA_1 |
||||
#define GPIO_I2C2_SCL_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN10) |
||||
#define GPIO_I2C2_SDA_GPIO (GPIO_OUTPUT|GPIO_OPENDRAIN|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN11) |
||||
|
||||
/*
|
||||
* I2C busses |
||||
*/ |
||||
#define PX4_I2C_BUS_EXPANSION 1 |
||||
#define PX4_I2C_BUS_LED 2 |
||||
|
||||
/*
|
||||
* Devices on the onboard bus. |
||||
* |
||||
* Note that these are unshifted addresses. |
||||
*/ |
||||
#define PX4_I2C_OBDEV_LED 0x5a |
||||
|
||||
/*
|
||||
* SPI |
||||
* |
||||
* There are sensors on SPI1, and SPI2 is connected to the FRAM. |
||||
*/ |
||||
#define GPIO_SPI1_MISO GPIO_SPI1_MISO_1 |
||||
#define GPIO_SPI1_MOSI GPIO_SPI1_MOSI_1 |
||||
#define GPIO_SPI1_SCK GPIO_SPI1_SCK_1 |
||||
|
||||
#define GPIO_SPI2_MISO GPIO_SPI2_MISO_1 |
||||
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1 |
||||
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2 |
||||
|
||||
/*
|
||||
* Use these in place of the spi_dev_e enumeration to |
||||
* select a specific SPI device on SPI1 |
||||
*/ |
||||
#define PX4_SPIDEV_GYRO 1 |
||||
#define PX4_SPIDEV_ACCEL_MAG 2 |
||||
#define PX4_SPIDEV_BARO 3 |
||||
|
||||
/*
|
||||
* Tone alarm output |
||||
*/ |
||||
#define TONE_ALARM_TIMER 2 /* timer 3 */ |
||||
#define TONE_ALARM_CHANNEL 1 /* channel 3 */ |
||||
#define GPIO_TONE_ALARM (GPIO_ALT|GPIO_AF2|GPIO_SPEED_2MHz|GPIO_FLOAT|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN15) |
||||
|
||||
/************************************************************************************
|
||||
* Public Data |
||||
************************************************************************************/ |
||||
|
||||
#ifndef __ASSEMBLY__ |
||||
|
||||
#undef EXTERN |
||||
#if defined(__cplusplus) |
||||
#define EXTERN extern "C" |
||||
extern "C" { |
||||
#else |
||||
#define EXTERN extern |
||||
#endif |
||||
|
||||
/************************************************************************************
|
||||
* Public Function Prototypes |
||||
************************************************************************************/ |
||||
/************************************************************************************
|
||||
* Name: stm32_boardinitialize |
||||
* |
||||
* Description: |
||||
* All STM32 architectures must provide the following entry point. This entry point |
||||
* is called early in the intitialization -- after all memory has been configured |
||||
* and mapped but before any devices have been initialized. |
||||
* |
||||
************************************************************************************/ |
||||
|
||||
EXTERN void stm32_boardinitialize(void); |
||||
|
||||
#undef EXTERN |
||||
#if defined(__cplusplus) |
||||
} |
||||
#endif |
||||
|
||||
#endif /* __ASSEMBLY__ */ |
||||
#endif /* __ARCH_BOARD_BOARD_H */ |
@ -0,0 +1,42 @@
@@ -0,0 +1,42 @@
|
||||
/****************************************************************************
|
||||
* |
||||
* Copyright (C) 2013 PX4 Development Team. All rights reserved. |
||||
* |
||||
* Redistribution and use in source and binary forms, with or without |
||||
* modification, are permitted provided that the following conditions |
||||
* are met: |
||||
* |
||||
* 1. Redistributions of source code must retain the above copyright |
||||
* notice, this list of conditions and the following disclaimer. |
||||
* 2. Redistributions in binary form must reproduce the above copyright |
||||
* notice, this list of conditions and the following disclaimer in |
||||
* the documentation and/or other materials provided with the |
||||
* distribution. |
||||
* 3. Neither the name PX4 nor the names of its contributors may be |
||||
* used to endorse or promote products derived from this software |
||||
* without specific prior written permission. |
||||
* |
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
* POSSIBILITY OF SUCH DAMAGE. |
||||
* |
||||
****************************************************************************/ |
||||
|
||||
/**
|
||||
* nsh_romfsetc.h |
||||
* |
||||
* This file is a stub for 'make export' purposes; the actual ROMFS |
||||
* must be supplied by the library client. |
||||
*/ |
||||
|
||||
extern unsigned char romfs_img[]; |
||||
extern unsigned int romfs_img_len; |
@ -0,0 +1,3 @@
@@ -0,0 +1,3 @@
|
||||
include ${TOPDIR}/.config |
||||
|
||||
include $(TOPDIR)/configs/px4fmu/common/Make.defs |
@ -0,0 +1,143 @@
@@ -0,0 +1,143 @@
|
||||
############################################################################ |
||||
# configs/px4fmu/nsh/appconfig |
||||
# |
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved. |
||||
# Author: Gregory Nutt <gnutt@nuttx.org> |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name NuttX nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
############################################################################ |
||||
|
||||
# Path to example in apps/examples containing the user_start entry point |
||||
|
||||
CONFIGURED_APPS += examples/nsh |
||||
|
||||
# The NSH application library |
||||
CONFIGURED_APPS += nshlib |
||||
CONFIGURED_APPS += system/readline |
||||
|
||||
# System library - utility functions |
||||
CONFIGURED_APPS += systemlib |
||||
CONFIGURED_APPS += systemlib/mixer |
||||
|
||||
# Math library |
||||
ifneq ($(CONFIG_APM),y) |
||||
CONFIGURED_APPS += mathlib |
||||
CONFIGURED_APPS += mathlib/CMSIS |
||||
CONFIGURED_APPS += examples/math_demo |
||||
endif |
||||
|
||||
# Control library |
||||
ifneq ($(CONFIG_APM),y) |
||||
CONFIGURED_APPS += controllib |
||||
CONFIGURED_APPS += examples/control_demo |
||||
CONFIGURED_APPS += examples/kalman_demo |
||||
endif |
||||
|
||||
# System utility commands |
||||
CONFIGURED_APPS += systemcmds/reboot |
||||
CONFIGURED_APPS += systemcmds/perf |
||||
CONFIGURED_APPS += systemcmds/top |
||||
CONFIGURED_APPS += systemcmds/boardinfo |
||||
CONFIGURED_APPS += systemcmds/mixer |
||||
# No I2C EEPROM - need new param interface |
||||
#CONFIGURED_APPS += systemcmds/eeprom |
||||
#CONFIGURED_APPS += systemcmds/param |
||||
CONFIGURED_APPS += systemcmds/pwm |
||||
CONFIGURED_APPS += systemcmds/bl_update |
||||
CONFIGURED_APPS += systemcmds/preflight_check |
||||
CONFIGURED_APPS += systemcmds/delay_test |
||||
|
||||
# Tutorial code from |
||||
# https://pixhawk.ethz.ch/px4/dev/hello_sky |
||||
# CONFIGURED_APPS += examples/px4_simple_app |
||||
|
||||
# Tutorial code from |
||||
# https://pixhawk.ethz.ch/px4/dev/deamon |
||||
# CONFIGURED_APPS += examples/px4_deamon_app |
||||
|
||||
# Tutorial code from |
||||
# https://pixhawk.ethz.ch/px4/dev/debug_values |
||||
# CONFIGURED_APPS += examples/px4_mavlink_debug |
||||
|
||||
# Shared object broker; required by many parts of the system. |
||||
CONFIGURED_APPS += uORB |
||||
|
||||
CONFIGURED_APPS += mavlink |
||||
CONFIGURED_APPS += mavlink_onboard |
||||
CONFIGURED_APPS += commander |
||||
CONFIGURED_APPS += sdlog |
||||
CONFIGURED_APPS += sensors |
||||
|
||||
ifneq ($(CONFIG_APM),y) |
||||
#CONFIGURED_APPS += ardrone_interface |
||||
CONFIGURED_APPS += multirotor_att_control |
||||
CONFIGURED_APPS += multirotor_pos_control |
||||
#CONFIGURED_APPS += fixedwing_control |
||||
CONFIGURED_APPS += fixedwing_att_control |
||||
CONFIGURED_APPS += fixedwing_pos_control |
||||
CONFIGURED_APPS += position_estimator |
||||
CONFIGURED_APPS += attitude_estimator_ekf |
||||
CONFIGURED_APPS += hott_telemetry |
||||
endif |
||||
|
||||
# Hacking tools |
||||
# XXX needs updating for new i2c config |
||||
#CONFIGURED_APPS += systemcmds/i2c |
||||
|
||||
# Communication and Drivers |
||||
CONFIGURED_APPS += drivers/boards/px4fmuv2 |
||||
CONFIGURED_APPS += drivers/device |
||||
# XXX needs conversion to SPI |
||||
#CONFIGURED_APPS += drivers/ms5611 |
||||
CONFIGURED_APPS += drivers/l3gd20 |
||||
# XXX needs conversion to serial |
||||
#CONFIGURED_APPS += drivers/px4io |
||||
CONFIGURED_APPS += drivers/stm32 |
||||
#CONFIGURED_APPS += drivers/led |
||||
CONFIGURED_APPS += drivers/blinkm |
||||
CONFIGURED_APPS += drivers/stm32/tone_alarm |
||||
CONFIGURED_APPS += drivers/stm32/adc |
||||
#CONFIGURED_APPS += drivers/px4fmu |
||||
CONFIGURED_APPS += drivers/hil |
||||
CONFIGURED_APPS += drivers/gps |
||||
CONFIGURED_APPS += drivers/mb12xx |
||||
|
||||
# Testing stuff |
||||
CONFIGURED_APPS += px4/sensors_bringup |
||||
CONFIGURED_APPS += px4/tests |
||||
|
||||
ifeq ($(CONFIG_CAN),y) |
||||
#CONFIGURED_APPS += examples/can |
||||
endif |
||||
|
||||
#ifeq ($(CONFIG_USBDEV),y) |
||||
#ifeq ($(CONFIG_CDCACM),y) |
||||
CONFIGURED_APPS += examples/cdcacm |
||||
#endif |
||||
#endif |
File diff suppressed because it is too large
Load Diff
@ -0,0 +1,67 @@
@@ -0,0 +1,67 @@
|
||||
#!/bin/bash |
||||
# configs/stm3240g-eval/nsh/setenv.sh |
||||
# |
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved. |
||||
# Author: Gregory Nutt <gnutt@nuttx.org> |
||||
# |
||||
# Redistribution and use in source and binary forms, with or without |
||||
# modification, are permitted provided that the following conditions |
||||
# are met: |
||||
# |
||||
# 1. Redistributions of source code must retain the above copyright |
||||
# notice, this list of conditions and the following disclaimer. |
||||
# 2. Redistributions in binary form must reproduce the above copyright |
||||
# notice, this list of conditions and the following disclaimer in |
||||
# the documentation and/or other materials provided with the |
||||
# distribution. |
||||
# 3. Neither the name NuttX nor the names of its contributors may be |
||||
# used to endorse or promote products derived from this software |
||||
# without specific prior written permission. |
||||
# |
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS |
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT |
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS |
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE |
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, |
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, |
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS |
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED |
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT |
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN |
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
||||
# POSSIBILITY OF SUCH DAMAGE. |
||||
# |
||||
|
||||
if [ "$_" = "$0" ] ; then |
||||
echo "You must source this script, not run it!" 1>&2 |
||||
exit 1 |
||||
fi |
||||
|
||||
WD=`pwd` |
||||
if [ ! -x "setenv.sh" ]; then |
||||
echo "This script must be executed from the top-level NuttX build directory" |
||||
exit 1 |
||||
fi |
||||
|
||||
if [ -z "${PATH_ORIG}" ]; then |
||||
export PATH_ORIG="${PATH}" |
||||
fi |
||||
|
||||
# This the Cygwin path to the location where I installed the RIDE |
||||
# toolchain under windows. You will also have to edit this if you install |
||||
# the RIDE toolchain in any other location |
||||
#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin" |
||||
|
||||
# This the Cygwin path to the location where I installed the CodeSourcery |
||||
# toolchain under windows. You will also have to edit this if you install |
||||
# the CodeSourcery toolchain in any other location |
||||
export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin" |
||||
|
||||
# This the Cygwin path to the location where I build the buildroot |
||||
# toolchain. |
||||
#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin" |
||||
|
||||
# Add the path to the toolchain to the PATH varialble |
||||
export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}" |
||||
|
||||
echo "PATH : ${PATH}" |
@ -0,0 +1,84 @@
@@ -0,0 +1,84 @@
|
||||
############################################################################
|
||||
# configs/px4fmu/src/Makefile
|
||||
#
|
||||
# Copyright (C) 2011 Gregory Nutt. All rights reserved.
|
||||
# Author: Gregory Nutt <gnutt@nuttx.org>
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name NuttX nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
-include $(TOPDIR)/Make.defs |
||||
|
||||
CFLAGS += -I$(TOPDIR)/sched
|
||||
|
||||
ASRCS =
|
||||
AOBJS = $(ASRCS:.S=$(OBJEXT))
|
||||
|
||||
CSRCS = empty.c
|
||||
COBJS = $(CSRCS:.c=$(OBJEXT))
|
||||
|
||||
SRCS = $(ASRCS) $(CSRCS)
|
||||
OBJS = $(AOBJS) $(COBJS)
|
||||
|
||||
ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
|
||||
ifeq ($(WINTOOL),y) |
||||
CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
|
||||
-I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
|
||||
else |
||||
CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
|
||||
endif |
||||
|
||||
all: libboard$(LIBEXT) |
||||
|
||||
$(AOBJS): %$(OBJEXT): %.S |
||||
$(call ASSEMBLE, $<, $@)
|
||||
|
||||
$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c |
||||
$(call COMPILE, $<, $@)
|
||||
|
||||
libboard$(LIBEXT): $(OBJS) |
||||
$(call ARCHIVE, $@, $(OBJS))
|
||||
|
||||
.depend: Makefile $(SRCS) |
||||
$(Q) $(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
|
||||
$(Q) touch $@
|
||||
|
||||
depend: .depend |
||||
|
||||
clean: |
||||
$(call DELFILE, libboard$(LIBEXT))
|
||||
$(call CLEAN)
|
||||
|
||||
distclean: clean |
||||
$(call DELFILE, Make.dep)
|
||||
$(call DELFILE, .depend)
|
||||
|
||||
-include Make.dep |
||||
|
Loading…
Reference in new issue