forked from Archive/PX4-Autopilot
Merge branch 'export-build' of https://github.com/PX4/Firmware into fmuv2_bringup
This commit is contained in:
commit
a7fc1b74bf
1
Makefile
1
Makefile
|
@ -43,7 +43,6 @@ include $(PX4_BASE)makefiles/setup.mk
|
|||
# Canned firmware configurations that we build.
|
||||
#
|
||||
CONFIGS ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
|
||||
#CONFIGS ?= px4fmu_default px4io_default
|
||||
|
||||
#
|
||||
# Boards that we build NuttX export kits for.
|
||||
|
|
|
@ -5,7 +5,7 @@ set USB no
|
|||
set MODE camflyer
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
|
@ -27,38 +27,65 @@ fi
|
|||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Start the sensors.
|
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
if [ -f /fs/microsd/px4io.bin ]
|
||||
then
|
||||
echo "PX4IO Firmware found. Checking Upgrade.."
|
||||
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
then
|
||||
echo "No newer version, skipping upgrade."
|
||||
else
|
||||
echo "Loading /fs/microsd/px4io.bin"
|
||||
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
|
||||
then
|
||||
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
|
||||
else
|
||||
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
|
||||
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start MAVLink
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander.
|
||||
# Start the commander (depends on orb, mavlink)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start GPS interface
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
kalman_demo start
|
||||
|
||||
#
|
||||
# Start PX4IO interface
|
||||
# Start PX4IO interface (depends on orb, commander)
|
||||
#
|
||||
px4io start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
kalman_demo start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
control_demo start
|
||||
|
@ -66,8 +93,8 @@ control_demo start
|
|||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog start -s 10
|
||||
|
||||
#sdlog start -s 4
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
|
|
|
@ -2,10 +2,10 @@
|
|||
#
|
||||
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
||||
#
|
||||
|
||||
|
||||
# Disable the USB interface
|
||||
set USB no
|
||||
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE ardrone
|
||||
|
||||
|
@ -25,13 +25,18 @@ if [ -f /fs/microsd/parameters ]
|
|||
then
|
||||
param load /fs/microsd/parameters
|
||||
fi
|
||||
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Start the sensors.
|
||||
|
@ -54,11 +59,6 @@ commander start
|
|||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Fire up the multi rotor attitude controller
|
||||
#
|
||||
|
@ -68,17 +68,17 @@ multirotor_att_control start
|
|||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start GPS capture
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog start -s 10
|
||||
|
||||
#
|
||||
# Start GPS capture
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
|
@ -95,4 +95,5 @@ fi
|
|||
# use the same UART for telemetry
|
||||
#
|
||||
echo "[init] startup done"
|
||||
exit
|
||||
|
||||
exit
|
||||
|
|
|
@ -21,9 +21,9 @@ set MODE autostart
|
|||
set USB autoconnect
|
||||
|
||||
#
|
||||
# Start playing the startup tune
|
||||
|
||||
#
|
||||
tone_alarm start
|
||||
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
|
@ -32,8 +32,12 @@ echo "[init] looking for microSD..."
|
|||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm 2
|
||||
fi
|
||||
|
||||
#
|
||||
|
|
|
@ -0,0 +1,7 @@
|
|||
Multirotor mixer for PX4FMU
|
||||
===========================
|
||||
|
||||
This file defines a single mixer for a quadrotor in the V configuration. All controls
|
||||
are mixed 100%.
|
||||
|
||||
R: 4v 10000 10000 10000 0
|
|
@ -1,107 +0,0 @@
|
|||
#!nsh
|
||||
|
||||
# Disable USB and autostart
|
||||
set USB no
|
||||
set MODE camflyer
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Load microSD params
|
||||
#
|
||||
echo "[init] loading microSD params"
|
||||
param select /fs/microsd/parameters
|
||||
if [ -f /fs/microsd/parameters ]
|
||||
then
|
||||
param load /fs/microsd/parameters
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
|
||||
#
|
||||
if [ -f /fs/microsd/px4io.bin ]
|
||||
then
|
||||
echo "PX4IO Firmware found. Checking Upgrade.."
|
||||
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
then
|
||||
echo "No newer version, skipping upgrade."
|
||||
else
|
||||
echo "Loading /fs/microsd/px4io.bin"
|
||||
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
|
||||
then
|
||||
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
|
||||
else
|
||||
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
|
||||
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander (depends on orb, mavlink)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start PX4IO interface (depends on orb, commander)
|
||||
#
|
||||
px4io start
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
kalman_demo start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
control_demo start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
|
@ -1,99 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
||||
#
|
||||
|
||||
# Disable the USB interface
|
||||
set USB no
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE ardrone
|
||||
|
||||
echo "[init] doing PX4IOAR startup..."
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Init the parameter storage
|
||||
#
|
||||
echo "[init] loading microSD params"
|
||||
param select /fs/microsd/parameters
|
||||
if [ -f /fs/microsd/parameters ]
|
||||
then
|
||||
param load /fs/microsd/parameters
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Start the sensors.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start MAVLink
|
||||
#
|
||||
mavlink start -d /dev/ttyS0 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander.
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Fire up the multi rotor attitude controller
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog start -s 10
|
||||
|
||||
#
|
||||
# Start GPS capture
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
|
||||
#
|
||||
# startup is done; we don't want the shell because we
|
||||
# use the same UART for telemetry
|
||||
#
|
||||
echo "[init] startup done"
|
||||
|
||||
exit
|
|
@ -1,83 +0,0 @@
|
|||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script.
|
||||
#
|
||||
# This script is responsible for:
|
||||
#
|
||||
# - mounting the microSD card (if present)
|
||||
# - running the user startup script from the microSD card (if present)
|
||||
# - detecting the configuration of the system and picking a suitable
|
||||
# startup script to continue with
|
||||
#
|
||||
# Note: DO NOT add configuration-specific commands to this script;
|
||||
# add them to the per-configuration scripts instead.
|
||||
#
|
||||
|
||||
#
|
||||
# Default to auto-start mode. An init script on the microSD card
|
||||
# can change this to prevent automatic startup of the flight script.
|
||||
#
|
||||
set MODE autostart
|
||||
set USB autoconnect
|
||||
|
||||
#
|
||||
|
||||
#
|
||||
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm 2
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
#
|
||||
# To prevent automatic startup in the current flight mode,
|
||||
# the script should set MODE to some other value.
|
||||
#
|
||||
if [ -f /fs/microsd/etc/rc ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc"
|
||||
sh /fs/microsd/etc/rc
|
||||
fi
|
||||
# Also consider rc.txt files
|
||||
if [ -f /fs/microsd/etc/rc.txt ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
||||
sh /fs/microsd/etc/rc.txt
|
||||
fi
|
||||
|
||||
#
|
||||
# Check for USB host
|
||||
#
|
||||
if [ $USB != autoconnect ]
|
||||
then
|
||||
echo "[init] not connecting USB"
|
||||
else
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
else
|
||||
echo "[init] No USB connected"
|
||||
fi
|
||||
fi
|
||||
|
||||
# if this is an APM build then there will be a rc.APM script
|
||||
# from an EXTERNAL_SCRIPTS build option
|
||||
if [ -f /etc/init.d/rc.APM ]
|
||||
then
|
||||
echo Running rc.APM
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
fi
|
|
@ -1,41 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# 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 PX4FMU
|
||||
#
|
||||
|
||||
INCLUDES = $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common
|
||||
LIBNAME = brd_px4fmu
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
|
@ -1,141 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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"
|
||||
|
||||
/************************************************************************************
|
||||
* 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;
|
||||
}
|
|
@ -1,232 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 *spi3;
|
||||
|
||||
#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
|
||||
drv_led_start();
|
||||
up_ledoff(LED_BLUE);
|
||||
up_ledoff(LED_AMBER);
|
||||
up_ledon(LED_BLUE);
|
||||
|
||||
/* 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, false);
|
||||
SPI_SELECT(spi1, PX4_SPIDEV_MPU, false);
|
||||
up_udelay(20);
|
||||
|
||||
message("[boot] Successfully initialized SPI port 1\r\n");
|
||||
|
||||
/* Get the SPI port for the microSD slot */
|
||||
|
||||
message("[boot] Initializing SPI port 3\n");
|
||||
spi3 = up_spiinitialize(3);
|
||||
|
||||
if (!spi3) {
|
||||
message("[boot] FAILED to initialize SPI port 3\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
message("[boot] Successfully initialized SPI port 3\n");
|
||||
|
||||
/* Now bind the SPI interface to the MMCSD driver */
|
||||
result = mmcsd_spislotinitialize(CONFIG_NSH_MMCSDMINOR, CONFIG_NSH_MMCSDSLOTNO, spi3);
|
||||
|
||||
if (result != OK) {
|
||||
message("[boot] FAILED to bind SPI port 3 to the MMCSD driver\n");
|
||||
up_ledon(LED_AMBER);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
message("[boot] Successfully bound SPI port 3 to the MMCSD driver\n");
|
||||
|
||||
stm32_configgpio(GPIO_ADC1_IN10);
|
||||
stm32_configgpio(GPIO_ADC1_IN11);
|
||||
stm32_configgpio(GPIO_ADC1_IN12);
|
||||
stm32_configgpio(GPIO_ADC1_IN13); // jumperable to MPU6000 DRDY on some boards
|
||||
|
||||
return OK;
|
||||
}
|
|
@ -1,161 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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 ************************************************************************************/
|
||||
|
||||
#ifdef CONFIG_STM32_SPI2
|
||||
# error "SPI2 is not supported on this board"
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_STM32_CAN1)
|
||||
# warning "CAN1 is not supported on this board"
|
||||
#endif
|
||||
|
||||
/* PX4FMU GPIOs ***********************************************************************************/
|
||||
/* LEDs */
|
||||
|
||||
#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
|
||||
#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
|
||||
|
||||
/* External interrupts */
|
||||
#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
|
||||
// XXX MPU6000 DRDY?
|
||||
|
||||
/* SPI chip selects */
|
||||
#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
|
||||
#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
|
||||
#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
|
||||
|
||||
/* User GPIOs
|
||||
*
|
||||
* GPIO0-1 are the buffered high-power GPIOs.
|
||||
* GPIO2-5 are the USART2 pins.
|
||||
* GPIO6-7 are the CAN2 pins.
|
||||
*/
|
||||
#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2)
|
||||
#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
|
||||
#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
|
||||
#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
|
||||
#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
|
||||
#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
|
||||
#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
|
||||
#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
|
||||
#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
|
||||
|
||||
/* 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)
|
||||
|
||||
/* PWM
|
||||
*
|
||||
* The PX4FMU has five PWM outputs, of which only the output on
|
||||
* pin PC8 is fixed assigned to this function. The other four possible
|
||||
* pwm sources are the TX, RX, RTS and CTS pins of USART2
|
||||
*
|
||||
* Alternate function mapping:
|
||||
* PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
|
||||
*/
|
||||
|
||||
#ifdef CONFIG_PWM
|
||||
# if defined(CONFIG_STM32_TIM3_PWM)
|
||||
# define BUZZER_PWMCHANNEL 3
|
||||
# define BUZZER_PWMTIMER 3
|
||||
# elif defined(CONFIG_STM32_TIM8_PWM)
|
||||
# define BUZZER_PWMCHANNEL 3
|
||||
# define BUZZER_PWMTIMER 8
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/****************************************************************************************************
|
||||
* 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
|
|
@ -1,87 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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_TIM2_BASE,
|
||||
.clock_register = STM32_RCC_APB1ENR,
|
||||
.clock_bit = RCC_APB1ENR_TIM2EN,
|
||||
.clock_freq = STM32_APB1_TIM2_CLKIN
|
||||
}
|
||||
};
|
||||
|
||||
__EXPORT const struct pwm_servo_channel pwm_channels[PWM_SERVO_MAX_CHANNELS] = {
|
||||
{
|
||||
.gpio = GPIO_TIM2_CH1OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 1,
|
||||
.default_value = 1000,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM2_CH2OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 2,
|
||||
.default_value = 1000,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM2_CH3OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 3,
|
||||
.default_value = 1000,
|
||||
},
|
||||
{
|
||||
.gpio = GPIO_TIM2_CH4OUT,
|
||||
.timer_index = 0,
|
||||
.timer_channel = 4,
|
||||
.default_value = 1000,
|
||||
}
|
||||
};
|
|
@ -1,136 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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)
|
||||
{
|
||||
stm32_configgpio(GPIO_SPI_CS_GYRO);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL);
|
||||
stm32_configgpio(GPIO_SPI_CS_MPU);
|
||||
stm32_configgpio(GPIO_SPI_CS_SDCARD);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
* required for some peripheral
|
||||
* state machines
|
||||
*/
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_SDCARD, 1);
|
||||
}
|
||||
|
||||
__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_MPU, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_ACCEL:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_MPU:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
|
||||
break;
|
||||
|
||||
default:
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
||||
|
||||
__EXPORT void stm32_spi3select(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_SDCARD, !selected);
|
||||
}
|
||||
|
||||
__EXPORT uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
|
||||
{
|
||||
/* this is actually bogus, but PX4 has no way to sense the presence of an SD card */
|
||||
return SPI_STATUS_PRESENT;
|
||||
}
|
||||
|
|
@ -1,108 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* 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);
|
||||
}
|
||||
|
|
@ -1,571 +0,0 @@
|
|||
/************************************************************************************
|
||||
* Driver for 24xxxx-style I2C EEPROMs.
|
||||
*
|
||||
* Adapted from:
|
||||
*
|
||||
* drivers/mtd/at24xx.c
|
||||
* Driver for I2C-based at24cxx EEPROM(at24c32,at24c64,at24c128,at24c256)
|
||||
*
|
||||
* Copyright (C) 2011 Li Zhuoyi. All rights reserved.
|
||||
* Author: Li Zhuoyi <lzyy.cn@gmail.com>
|
||||
* History: 0.1 2011-08-20 initial version
|
||||
*
|
||||
* 2011-11-1 Added support for larger MTD block sizes: Hal Glenn <hglenn@2g-eng.com>
|
||||
*
|
||||
* Derived from drivers/mtd/m25px.c
|
||||
*
|
||||
* Copyright (C) 2009-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.
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Included Files
|
||||
************************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <string.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/mtd.h>
|
||||
|
||||
#include "systemlib/perf_counter.h"
|
||||
|
||||
/************************************************************************************
|
||||
* Pre-processor Definitions
|
||||
************************************************************************************/
|
||||
|
||||
/*
|
||||
* Configuration is as for the AT24 driver, but the CONFIG_MTD_AT24XX define should be
|
||||
* omitted in order to avoid building the AT24XX driver as well.
|
||||
*/
|
||||
|
||||
/* As a minimum, the size of the AT24 part and its 7-bit I2C address are required. */
|
||||
|
||||
#ifndef CONFIG_AT24XX_SIZE
|
||||
# warning "Assuming AT24 size 64"
|
||||
# define CONFIG_AT24XX_SIZE 64
|
||||
#endif
|
||||
#ifndef CONFIG_AT24XX_ADDR
|
||||
# warning "Assuming AT24 address of 0x50"
|
||||
# define CONFIG_AT24XX_ADDR 0x50
|
||||
#endif
|
||||
|
||||
/* Get the part configuration based on the size configuration */
|
||||
|
||||
#if CONFIG_AT24XX_SIZE == 32
|
||||
# define AT24XX_NPAGES 128
|
||||
# define AT24XX_PAGESIZE 32
|
||||
#elif CONFIG_AT24XX_SIZE == 48
|
||||
# define AT24XX_NPAGES 192
|
||||
# define AT24XX_PAGESIZE 32
|
||||
#elif CONFIG_AT24XX_SIZE == 64
|
||||
# define AT24XX_NPAGES 256
|
||||
# define AT24XX_PAGESIZE 32
|
||||
#elif CONFIG_AT24XX_SIZE == 128
|
||||
# define AT24XX_NPAGES 256
|
||||
# define AT24XX_PAGESIZE 64
|
||||
#elif CONFIG_AT24XX_SIZE == 256
|
||||
# define AT24XX_NPAGES 512
|
||||
# define AT24XX_PAGESIZE 64
|
||||
#endif
|
||||
|
||||
/* For applications where a file system is used on the AT24, the tiny page sizes
|
||||
* will result in very inefficient FLASH usage. In such cases, it is better if
|
||||
* blocks are comprised of "clusters" of pages so that the file system block
|
||||
* size is, say, 256 or 512 bytes. In any event, the block size *must* be an
|
||||
* even multiple of the pages.
|
||||
*/
|
||||
|
||||
#ifndef CONFIG_AT24XX_MTD_BLOCKSIZE
|
||||
# warning "Assuming driver block size is the same as the FLASH page size"
|
||||
# define CONFIG_AT24XX_MTD_BLOCKSIZE AT24XX_PAGESIZE
|
||||
#endif
|
||||
|
||||
/* The AT24 does not respond on the bus during write cycles, so we depend on a long
|
||||
* timeout to detect problems. The max program time is typically ~5ms.
|
||||
*/
|
||||
#ifndef CONFIG_AT24XX_WRITE_TIMEOUT_MS
|
||||
# define CONFIG_AT24XX_WRITE_TIMEOUT_MS 20
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Private Types
|
||||
************************************************************************************/
|
||||
|
||||
/* This type represents the state of the MTD device. The struct mtd_dev_s
|
||||
* must appear at the beginning of the definition so that you can freely
|
||||
* cast between pointers to struct mtd_dev_s and struct at24c_dev_s.
|
||||
*/
|
||||
|
||||
struct at24c_dev_s {
|
||||
struct mtd_dev_s mtd; /* MTD interface */
|
||||
FAR struct i2c_dev_s *dev; /* Saved I2C interface instance */
|
||||
uint8_t addr; /* I2C address */
|
||||
uint16_t pagesize; /* 32, 63 */
|
||||
uint16_t npages; /* 128, 256, 512, 1024 */
|
||||
|
||||
perf_counter_t perf_reads;
|
||||
perf_counter_t perf_writes;
|
||||
perf_counter_t perf_resets;
|
||||
perf_counter_t perf_read_retries;
|
||||
perf_counter_t perf_read_errors;
|
||||
perf_counter_t perf_write_errors;
|
||||
};
|
||||
|
||||
/************************************************************************************
|
||||
* Private Function Prototypes
|
||||
************************************************************************************/
|
||||
|
||||
/* MTD driver methods */
|
||||
|
||||
static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks);
|
||||
static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
|
||||
size_t nblocks, FAR uint8_t *buf);
|
||||
static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock,
|
||||
size_t nblocks, FAR const uint8_t *buf);
|
||||
static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg);
|
||||
|
||||
void at24c_test(void);
|
||||
|
||||
/************************************************************************************
|
||||
* Private Data
|
||||
************************************************************************************/
|
||||
|
||||
/* At present, only a single AT24 part is supported. In this case, a statically
|
||||
* allocated state structure may be used.
|
||||
*/
|
||||
|
||||
static struct at24c_dev_s g_at24c;
|
||||
|
||||
/************************************************************************************
|
||||
* Private Functions
|
||||
************************************************************************************/
|
||||
|
||||
static int at24c_eraseall(FAR struct at24c_dev_s *priv)
|
||||
{
|
||||
int startblock = 0;
|
||||
uint8_t buf[AT24XX_PAGESIZE + 2];
|
||||
|
||||
struct i2c_msg_s msgv[1] = {
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &buf[0],
|
||||
.length = sizeof(buf),
|
||||
}
|
||||
};
|
||||
|
||||
memset(&buf[2], 0xff, priv->pagesize);
|
||||
|
||||
for (startblock = 0; startblock < priv->npages; startblock++) {
|
||||
uint16_t offset = startblock * priv->pagesize;
|
||||
buf[1] = offset & 0xff;
|
||||
buf[0] = (offset >> 8) & 0xff;
|
||||
|
||||
while (I2C_TRANSFER(priv->dev, &msgv[0], 1) < 0) {
|
||||
fvdbg("erase stall\n");
|
||||
usleep(10000);
|
||||
}
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_erase
|
||||
************************************************************************************/
|
||||
|
||||
static int at24c_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks)
|
||||
{
|
||||
/* EEprom need not erase */
|
||||
|
||||
return (int)nblocks;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_test
|
||||
************************************************************************************/
|
||||
|
||||
void at24c_test(void)
|
||||
{
|
||||
uint8_t buf[CONFIG_AT24XX_MTD_BLOCKSIZE];
|
||||
unsigned count = 0;
|
||||
unsigned errors = 0;
|
||||
|
||||
for (count = 0; count < 10000; count++) {
|
||||
ssize_t result = at24c_bread(&g_at24c.mtd, 0, 1, buf);
|
||||
if (result == ERROR) {
|
||||
if (errors++ > 2) {
|
||||
vdbg("too many errors\n");
|
||||
return;
|
||||
}
|
||||
} else if (result != 1) {
|
||||
vdbg("unexpected %u\n", result);
|
||||
}
|
||||
if ((count % 100) == 0)
|
||||
vdbg("test %u errors %u\n", count, errors);
|
||||
}
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_bread
|
||||
************************************************************************************/
|
||||
|
||||
static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock,
|
||||
size_t nblocks, FAR uint8_t *buffer)
|
||||
{
|
||||
FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
|
||||
size_t blocksleft;
|
||||
uint8_t addr[2];
|
||||
int ret;
|
||||
|
||||
struct i2c_msg_s msgv[2] = {
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &addr[0],
|
||||
.length = sizeof(addr),
|
||||
},
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = 0,
|
||||
.length = priv->pagesize,
|
||||
}
|
||||
};
|
||||
|
||||
#if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
|
||||
startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
#endif
|
||||
blocksleft = nblocks;
|
||||
|
||||
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
if (startblock >= priv->npages) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (startblock + nblocks > priv->npages) {
|
||||
nblocks = priv->npages - startblock;
|
||||
}
|
||||
|
||||
while (blocksleft-- > 0) {
|
||||
uint16_t offset = startblock * priv->pagesize;
|
||||
unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS;
|
||||
|
||||
addr[1] = offset & 0xff;
|
||||
addr[0] = (offset >> 8) & 0xff;
|
||||
msgv[1].buffer = buffer;
|
||||
|
||||
for (;;) {
|
||||
|
||||
perf_begin(priv->perf_reads);
|
||||
ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
|
||||
perf_end(priv->perf_reads);
|
||||
|
||||
if (ret >= 0)
|
||||
break;
|
||||
|
||||
fvdbg("read stall");
|
||||
usleep(1000);
|
||||
|
||||
/* We should normally only be here on the first read after
|
||||
* a write.
|
||||
*
|
||||
* XXX maybe do special first-read handling with optional
|
||||
* bus reset as well?
|
||||
*/
|
||||
perf_count(priv->perf_read_retries);
|
||||
|
||||
if (--tries == 0) {
|
||||
perf_count(priv->perf_read_errors);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
startblock++;
|
||||
buffer += priv->pagesize;
|
||||
}
|
||||
|
||||
#if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
|
||||
return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
#else
|
||||
return nblocks;
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_bwrite
|
||||
*
|
||||
* Operates on MTD block's and translates to FLASH pages
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks,
|
||||
FAR const uint8_t *buffer)
|
||||
{
|
||||
FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
|
||||
size_t blocksleft;
|
||||
uint8_t buf[AT24XX_PAGESIZE + 2];
|
||||
int ret;
|
||||
|
||||
struct i2c_msg_s msgv[1] = {
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &buf[0],
|
||||
.length = sizeof(buf),
|
||||
}
|
||||
};
|
||||
|
||||
#if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
|
||||
startblock *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
nblocks *= (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
#endif
|
||||
blocksleft = nblocks;
|
||||
|
||||
if (startblock >= priv->npages) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (startblock + nblocks > priv->npages) {
|
||||
nblocks = priv->npages - startblock;
|
||||
}
|
||||
|
||||
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
|
||||
|
||||
while (blocksleft-- > 0) {
|
||||
uint16_t offset = startblock * priv->pagesize;
|
||||
unsigned tries = CONFIG_AT24XX_WRITE_TIMEOUT_MS;
|
||||
|
||||
buf[1] = offset & 0xff;
|
||||
buf[0] = (offset >> 8) & 0xff;
|
||||
memcpy(&buf[2], buffer, priv->pagesize);
|
||||
|
||||
for (;;) {
|
||||
|
||||
perf_begin(priv->perf_writes);
|
||||
ret = I2C_TRANSFER(priv->dev, &msgv[0], 1);
|
||||
perf_end(priv->perf_writes);
|
||||
|
||||
if (ret >= 0)
|
||||
break;
|
||||
|
||||
fvdbg("write stall");
|
||||
usleep(1000);
|
||||
|
||||
/* We expect to see a number of retries per write cycle as we
|
||||
* poll for write completion.
|
||||
*/
|
||||
if (--tries == 0) {
|
||||
perf_count(priv->perf_write_errors);
|
||||
return ERROR;
|
||||
}
|
||||
}
|
||||
|
||||
startblock++;
|
||||
buffer += priv->pagesize;
|
||||
}
|
||||
|
||||
#if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
|
||||
return nblocks / (CONFIG_AT24XX_MTD_BLOCKSIZE / AT24XX_PAGESIZE);
|
||||
#else
|
||||
return nblocks;
|
||||
#endif
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_ioctl
|
||||
************************************************************************************/
|
||||
|
||||
static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg)
|
||||
{
|
||||
FAR struct at24c_dev_s *priv = (FAR struct at24c_dev_s *)dev;
|
||||
int ret = -EINVAL; /* Assume good command with bad parameters */
|
||||
|
||||
fvdbg("cmd: %d \n", cmd);
|
||||
|
||||
switch (cmd) {
|
||||
case MTDIOC_GEOMETRY: {
|
||||
FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg);
|
||||
|
||||
if (geo) {
|
||||
/* Populate the geometry structure with information need to know
|
||||
* the capacity and how to access the device.
|
||||
*
|
||||
* NOTE: that the device is treated as though it where just an array
|
||||
* of fixed size blocks. That is most likely not true, but the client
|
||||
* will expect the device logic to do whatever is necessary to make it
|
||||
* appear so.
|
||||
*
|
||||
* blocksize:
|
||||
* May be user defined. The block size for the at24XX devices may be
|
||||
* larger than the page size in order to better support file systems.
|
||||
* The read and write functions translate BLOCKS to pages for the
|
||||
* small flash devices
|
||||
* erasesize:
|
||||
* It has to be at least as big as the blocksize, bigger serves no
|
||||
* purpose.
|
||||
* neraseblocks
|
||||
* Note that the device size is in kilobits and must be scaled by
|
||||
* 1024 / 8
|
||||
*/
|
||||
|
||||
#if CONFIG_AT24XX_MTD_BLOCKSIZE > AT24XX_PAGESIZE
|
||||
geo->blocksize = CONFIG_AT24XX_MTD_BLOCKSIZE;
|
||||
geo->erasesize = CONFIG_AT24XX_MTD_BLOCKSIZE;
|
||||
geo->neraseblocks = (CONFIG_AT24XX_SIZE * 1024 / 8) / CONFIG_AT24XX_MTD_BLOCKSIZE;
|
||||
#else
|
||||
geo->blocksize = priv->pagesize;
|
||||
geo->erasesize = priv->pagesize;
|
||||
geo->neraseblocks = priv->npages;
|
||||
#endif
|
||||
ret = OK;
|
||||
|
||||
fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n",
|
||||
geo->blocksize, geo->erasesize, geo->neraseblocks);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case MTDIOC_BULKERASE:
|
||||
ret = at24c_eraseall(priv);
|
||||
break;
|
||||
|
||||
case MTDIOC_XIPBASE:
|
||||
default:
|
||||
ret = -ENOTTY; /* Bad command */
|
||||
break;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/************************************************************************************
|
||||
* Public Functions
|
||||
************************************************************************************/
|
||||
|
||||
/************************************************************************************
|
||||
* Name: at24c_initialize
|
||||
*
|
||||
* Description:
|
||||
* Create an initialize MTD device instance. MTD devices are not registered
|
||||
* in the file system, but are created as instances that can be bound to
|
||||
* other functions (such as a block or character driver front end).
|
||||
*
|
||||
************************************************************************************/
|
||||
|
||||
FAR struct mtd_dev_s *at24c_initialize(FAR struct i2c_dev_s *dev) {
|
||||
FAR struct at24c_dev_s *priv;
|
||||
|
||||
fvdbg("dev: %p\n", dev);
|
||||
|
||||
/* Allocate a state structure (we allocate the structure instead of using
|
||||
* a fixed, static allocation so that we can handle multiple FLASH devices.
|
||||
* The current implementation would handle only one FLASH part per I2C
|
||||
* device (only because of the SPIDEV_FLASH definition) and so would have
|
||||
* to be extended to handle multiple FLASH parts on the same I2C bus.
|
||||
*/
|
||||
|
||||
priv = &g_at24c;
|
||||
|
||||
if (priv) {
|
||||
/* Initialize the allocated structure */
|
||||
|
||||
priv->addr = CONFIG_AT24XX_ADDR;
|
||||
priv->pagesize = AT24XX_PAGESIZE;
|
||||
priv->npages = AT24XX_NPAGES;
|
||||
|
||||
priv->mtd.erase = at24c_erase;
|
||||
priv->mtd.bread = at24c_bread;
|
||||
priv->mtd.bwrite = at24c_bwrite;
|
||||
priv->mtd.ioctl = at24c_ioctl;
|
||||
priv->dev = dev;
|
||||
|
||||
priv->perf_reads = perf_alloc(PC_ELAPSED, "EEPROM read");
|
||||
priv->perf_writes = perf_alloc(PC_ELAPSED, "EEPROM write");
|
||||
priv->perf_resets = perf_alloc(PC_COUNT, "EEPROM reset");
|
||||
priv->perf_read_retries = perf_alloc(PC_COUNT, "EEPROM read retries");
|
||||
priv->perf_read_errors = perf_alloc(PC_COUNT, "EEPROM read errors");
|
||||
priv->perf_write_errors = perf_alloc(PC_COUNT, "EEPROM write errors");
|
||||
}
|
||||
|
||||
/* attempt to read to validate device is present */
|
||||
unsigned char buf[5];
|
||||
uint8_t addrbuf[2] = {0, 0};
|
||||
|
||||
struct i2c_msg_s msgv[2] = {
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = 0,
|
||||
.buffer = &addrbuf[0],
|
||||
.length = sizeof(addrbuf),
|
||||
},
|
||||
{
|
||||
.addr = priv->addr,
|
||||
.flags = I2C_M_READ,
|
||||
.buffer = &buf[0],
|
||||
.length = sizeof(buf),
|
||||
}
|
||||
};
|
||||
|
||||
perf_begin(priv->perf_reads);
|
||||
int ret = I2C_TRANSFER(priv->dev, &msgv[0], 2);
|
||||
perf_end(priv->perf_reads);
|
||||
|
||||
if (ret < 0) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/* Return the implementation-specific state structure as the MTD device */
|
||||
|
||||
fvdbg("Return %p\n", priv);
|
||||
return (FAR struct mtd_dev_s *)priv;
|
||||
}
|
||||
|
||||
/*
|
||||
* XXX: debug hackery
|
||||
*/
|
||||
int at24c_nuke(void)
|
||||
{
|
||||
return at24c_eraseall(&g_at24c);
|
||||
}
|
|
@ -1,45 +0,0 @@
|
|||
############################################################################
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build the eeprom tool.
|
||||
#
|
||||
|
||||
APPNAME = eeprom
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 4096
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
|
@ -1,265 +0,0 @@
|
|||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* 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 eeprom.c
|
||||
*
|
||||
* EEPROM service and utility app.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <sys/mount.h>
|
||||
#include <sys/ioctl.h>
|
||||
#include <sys/stat.h>
|
||||
|
||||
#include <nuttx/i2c.h>
|
||||
#include <nuttx/mtd.h>
|
||||
#include <nuttx/fs/nxffs.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/param/param.h"
|
||||
#include "systemlib/err.h"
|
||||
|
||||
#ifndef PX4_I2C_BUS_ONBOARD
|
||||
# error PX4_I2C_BUS_ONBOARD not defined, cannot locate onboard EEPROM
|
||||
#endif
|
||||
|
||||
__EXPORT int eeprom_main(int argc, char *argv[]);
|
||||
|
||||
static void eeprom_attach(void);
|
||||
static void eeprom_start(void);
|
||||
static void eeprom_erase(void);
|
||||
static void eeprom_ioctl(unsigned operation);
|
||||
static void eeprom_save(const char *name);
|
||||
static void eeprom_load(const char *name);
|
||||
static void eeprom_test(void);
|
||||
|
||||
static bool attached = false;
|
||||
static bool started = false;
|
||||
static struct mtd_dev_s *eeprom_mtd;
|
||||
|
||||
int eeprom_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc >= 2) {
|
||||
if (!strcmp(argv[1], "start"))
|
||||
eeprom_start();
|
||||
|
||||
if (!strcmp(argv[1], "save_param"))
|
||||
eeprom_save(argv[2]);
|
||||
|
||||
if (!strcmp(argv[1], "load_param"))
|
||||
eeprom_load(argv[2]);
|
||||
|
||||
if (!strcmp(argv[1], "erase"))
|
||||
eeprom_erase();
|
||||
|
||||
if (!strcmp(argv[1], "test"))
|
||||
eeprom_test();
|
||||
|
||||
if (0) { /* these actually require a file on the filesystem... */
|
||||
|
||||
if (!strcmp(argv[1], "reformat"))
|
||||
eeprom_ioctl(FIOC_REFORMAT);
|
||||
|
||||
if (!strcmp(argv[1], "repack"))
|
||||
eeprom_ioctl(FIOC_OPTIMIZE);
|
||||
}
|
||||
}
|
||||
|
||||
errx(1, "expected a command, try 'start'\n\t'save_param /eeprom/parameters'\n\t'load_param /eeprom/parameters'\n\t'erase'\n");
|
||||
}
|
||||
|
||||
|
||||
static void
|
||||
eeprom_attach(void)
|
||||
{
|
||||
/* find the right I2C */
|
||||
struct i2c_dev_s *i2c = up_i2cinitialize(PX4_I2C_BUS_ONBOARD);
|
||||
/* this resets the I2C bus, set correct bus speed again */
|
||||
I2C_SETFREQUENCY(i2c, 400000);
|
||||
|
||||
if (i2c == NULL)
|
||||
errx(1, "failed to locate I2C bus");
|
||||
|
||||
/* start the MTD driver, attempt 5 times */
|
||||
for (int i = 0; i < 5; i++) {
|
||||
eeprom_mtd = at24c_initialize(i2c);
|
||||
if (eeprom_mtd) {
|
||||
/* abort on first valid result */
|
||||
if (i > 0) {
|
||||
warnx("warning: EEPROM needed %d attempts to attach", i+1);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
/* if last attempt is still unsuccessful, abort */
|
||||
if (eeprom_mtd == NULL)
|
||||
errx(1, "failed to initialize EEPROM driver");
|
||||
|
||||
attached = true;
|
||||
}
|
||||
|
||||
static void
|
||||
eeprom_start(void)
|
||||
{
|
||||
int ret;
|
||||
|
||||
if (started)
|
||||
errx(1, "EEPROM already mounted");
|
||||
|
||||
if (!attached)
|
||||
eeprom_attach();
|
||||
|
||||
/* start NXFFS */
|
||||
ret = nxffs_initialize(eeprom_mtd);
|
||||
|
||||
if (ret < 0)
|
||||
errx(1, "failed to initialize NXFFS - erase EEPROM to reformat");
|
||||
|
||||
/* mount the EEPROM */
|
||||
ret = mount(NULL, "/eeprom", "nxffs", 0, NULL);
|
||||
|
||||
if (ret < 0)
|
||||
errx(1, "failed to mount /eeprom - erase EEPROM to reformat");
|
||||
|
||||
started = true;
|
||||
warnx("mounted EEPROM at /eeprom");
|
||||
exit(0);
|
||||
}
|
||||
|
||||
extern int at24c_nuke(void);
|
||||
|
||||
static void
|
||||
eeprom_erase(void)
|
||||
{
|
||||
if (!attached)
|
||||
eeprom_attach();
|
||||
|
||||
if (at24c_nuke())
|
||||
errx(1, "erase failed");
|
||||
|
||||
errx(0, "erase done, reboot now");
|
||||
}
|
||||
|
||||
static void
|
||||
eeprom_ioctl(unsigned operation)
|
||||
{
|
||||
int fd;
|
||||
|
||||
fd = open("/eeprom/.", 0);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "open /eeprom");
|
||||
|
||||
if (ioctl(fd, operation, 0) < 0)
|
||||
err(1, "ioctl");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
eeprom_save(const char *name)
|
||||
{
|
||||
if (!started)
|
||||
errx(1, "must be started first");
|
||||
|
||||
if (!name)
|
||||
err(1, "missing argument for device name, try '/eeprom/parameters'");
|
||||
|
||||
warnx("WARNING: 'eeprom save_param' deprecated - use 'param save' instead");
|
||||
|
||||
/* delete the file in case it exists */
|
||||
unlink(name);
|
||||
|
||||
/* create the file */
|
||||
int fd = open(name, O_WRONLY | O_CREAT | O_EXCL);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "opening '%s' failed", name);
|
||||
|
||||
int result = param_export(fd, false);
|
||||
close(fd);
|
||||
|
||||
if (result < 0) {
|
||||
unlink(name);
|
||||
errx(1, "error exporting to '%s'", name);
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
static void
|
||||
eeprom_load(const char *name)
|
||||
{
|
||||
if (!started)
|
||||
errx(1, "must be started first");
|
||||
|
||||
if (!name)
|
||||
err(1, "missing argument for device name, try '/eeprom/parameters'");
|
||||
|
||||
warnx("WARNING: 'eeprom load_param' deprecated - use 'param load' instead");
|
||||
|
||||
int fd = open(name, O_RDONLY);
|
||||
|
||||
if (fd < 0)
|
||||
err(1, "open '%s'", name);
|
||||
|
||||
int result = param_load(fd);
|
||||
close(fd);
|
||||
|
||||
if (result < 0)
|
||||
errx(1, "error importing from '%s'", name);
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
extern void at24c_test(void);
|
||||
|
||||
static void
|
||||
eeprom_test(void)
|
||||
{
|
||||
at24c_test();
|
||||
exit(0);
|
||||
}
|
|
@ -418,6 +418,7 @@ public:
|
|||
enum Geometry {
|
||||
QUAD_X = 0, /**< quad in X configuration */
|
||||
QUAD_PLUS, /**< quad in + configuration */
|
||||
QUAD_V, /**< quad in V configuration */
|
||||
HEX_X, /**< hex in X configuration */
|
||||
HEX_PLUS, /**< hex in + configuration */
|
||||
OCTA_X,
|
||||
|
|
|
@ -82,6 +82,12 @@ const MultirotorMixer::Rotor _config_quad_plus[] = {
|
|||
{ 0.000000, 1.000000, -1.00 },
|
||||
{ -0.000000, -1.000000, -1.00 },
|
||||
};
|
||||
const MultirotorMixer::Rotor _config_quad_v[] = {
|
||||
{ -0.927184, 0.374607, 1.00 },
|
||||
{ 0.694658, -0.719340, 1.00 },
|
||||
{ 0.927184, 0.374607, -1.00 },
|
||||
{ -0.694658, -0.719340, -1.00 },
|
||||
};
|
||||
const MultirotorMixer::Rotor _config_hex_x[] = {
|
||||
{ -1.000000, 0.000000, -1.00 },
|
||||
{ 1.000000, 0.000000, 1.00 },
|
||||
|
@ -121,6 +127,7 @@ const MultirotorMixer::Rotor _config_octa_plus[] = {
|
|||
const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
||||
&_config_quad_x[0],
|
||||
&_config_quad_plus[0],
|
||||
&_config_quad_v[0],
|
||||
&_config_hex_x[0],
|
||||
&_config_hex_plus[0],
|
||||
&_config_octa_x[0],
|
||||
|
@ -129,6 +136,7 @@ const MultirotorMixer::Rotor *_config_index[MultirotorMixer::Geometry::MAX_GEOME
|
|||
const unsigned _config_rotor_count[MultirotorMixer::Geometry::MAX_GEOMETRY] = {
|
||||
4, /* quad_x */
|
||||
4, /* quad_plus */
|
||||
4, /* quad_v */
|
||||
6, /* hex_x */
|
||||
6, /* hex_plus */
|
||||
8, /* octa_x */
|
||||
|
@ -184,6 +192,9 @@ MultirotorMixer::from_text(Mixer::ControlCallback control_cb, uintptr_t cb_handl
|
|||
} else if (!strcmp(geomname, "4x")) {
|
||||
geometry = MultirotorMixer::QUAD_X;
|
||||
|
||||
} else if (!strcmp(geomname, "4v")) {
|
||||
geometry = MultirotorMixer::QUAD_V;
|
||||
|
||||
} else if (!strcmp(geomname, "6+")) {
|
||||
geometry = MultirotorMixer::HEX_PLUS;
|
||||
|
||||
|
|
|
@ -20,6 +20,13 @@ set quad_plus {
|
|||
180 CW
|
||||
}
|
||||
|
||||
set quad_v {
|
||||
68 CCW
|
||||
-136 CCW
|
||||
-68 CW
|
||||
136 CW
|
||||
}
|
||||
|
||||
set hex_x {
|
||||
90 CW
|
||||
-90 CCW
|
||||
|
@ -60,7 +67,7 @@ set octa_plus {
|
|||
90 CW
|
||||
}
|
||||
|
||||
set tables {quad_x quad_plus hex_x hex_plus octa_x octa_plus}
|
||||
set tables {quad_x quad_plus quad_v hex_x hex_plus octa_x octa_plus}
|
||||
|
||||
proc factors {a d} { puts [format "\t{ %9.6f, %9.6f, %5.2f }," [rcos [expr $a + 90]] [rcos $a] [expr -$d]]}
|
||||
|
||||
|
|
|
@ -141,4 +141,4 @@ int can_devinit(void)
|
|||
return OK;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif
|
||||
|
|
|
@ -46,6 +46,7 @@
|
|||
#include <stdbool.h>
|
||||
#include <poll.h>
|
||||
#include <fcntl.h>
|
||||
#include <v1.0/common/mavlink.h>
|
||||
#include <float.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <sys/prctl.h>
|
||||
|
@ -65,11 +66,17 @@
|
|||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
#include "codegen/attitudeKalmanfilter_initialize.h"
|
||||
#include "codegen/attitudeKalmanfilter.h"
|
||||
#include "attitude_estimator_ekf_params.h"
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
|
@ -264,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
/* Main loop*/
|
||||
while (!thread_should_exit) {
|
||||
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = sub_raw, .events = POLLIN },
|
||||
{ .fd = sub_params, .events = POLLIN }
|
||||
};
|
||||
struct pollfd fds[2];
|
||||
fds[0].fd = sub_raw;
|
||||
fds[0].events = POLLIN;
|
||||
fds[1].fd = sub_params;
|
||||
fds[1].events = POLLIN;
|
||||
int ret = poll(fds, 2, 1000);
|
||||
|
||||
if (ret < 0) {
|
|
@ -1,6 +1,6 @@
|
|||
|
||||
MODULE_NAME = attitude_estimator_ekf
|
||||
SRCS = attitude_estimator_ekf_main.c \
|
||||
SRCS = attitude_estimator_ekf_main.cpp \
|
||||
attitude_estimator_ekf_params.c \
|
||||
codegen/attitudeKalmanfilter_initialize.c \
|
||||
codegen/attitudeKalmanfilter_terminate.c \
|
||||
|
|
Loading…
Reference in New Issue