Browse Source

Optimize size of system lib

sbg
Lorenz Meier 10 years ago
parent
commit
00c7cc019c
  1. 8
      ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil
  2. 2
      ROMFS/px4fmu_common/init.d/10015_tbs_discovery
  3. 2
      ROMFS/px4fmu_common/init.d/10016_3dr_iris
  4. 3
      ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d
  5. 2
      ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil
  6. 2
      ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil
  7. 4
      ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil
  8. 2
      ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil
  9. 4
      ROMFS/px4fmu_common/init.d/11001_hexa_cox
  10. 2
      ROMFS/px4fmu_common/init.d/12001_octo_cox
  11. 4
      ROMFS/px4fmu_common/init.d/3031_phantom
  12. 6
      ROMFS/px4fmu_common/init.d/3032_skywalker_x5
  13. 2
      ROMFS/px4fmu_common/init.d/3033_wingwing
  14. 2
      ROMFS/px4fmu_common/init.d/3034_fx79
  15. 2
      ROMFS/px4fmu_common/init.d/3035_viper
  16. 8
      ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha
  17. 2
      ROMFS/px4fmu_common/init.d/4001_quad_x
  18. 3
      ROMFS/px4fmu_common/init.d/4008_ardrone
  19. 4
      ROMFS/px4fmu_common/init.d/4010_dji_f330
  20. 4
      ROMFS/px4fmu_common/init.d/4011_dji_f450
  21. 2
      ROMFS/px4fmu_common/init.d/4012_quad_x_can
  22. 2
      ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb
  23. 2
      ROMFS/px4fmu_common/init.d/5001_quad_+
  24. 4
      ROMFS/px4fmu_common/init.d/6001_hexa_x
  25. 4
      ROMFS/px4fmu_common/init.d/7001_hexa_+
  26. 2
      ROMFS/px4fmu_common/init.d/8001_octo_x
  27. 2
      ROMFS/px4fmu_common/init.d/9001_octo_+
  28. 5
      ROMFS/px4fmu_common/init.d/rc.autostart
  29. 7
      ROMFS/px4fmu_common/init.d/rc.sensors
  30. 24
      ROMFS/px4fmu_common/init.d/rcS
  31. 109
      src/modules/systemlib/mcu_version.c
  32. 52
      src/modules/systemlib/mcu_version.h
  33. 3
      src/modules/systemlib/module.mk
  34. 90
      src/systemcmds/ver/ver.c

8
ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil

@ -1,14 +1,10 @@ @@ -1,14 +1,10 @@
#!nsh
#
# HILStar / X-Plane
#
# Lorenz Meier <lm@inf.ethz.ch>
# HILStar
# <lorenz@px4.io>
#
sh /etc/init.d/rc.fw_defaults
echo "X Plane HIL starting.."
set HIL yes
set MIXER FMU_AERT

2
ROMFS/px4fmu_common/init.d/10015_tbs_discovery

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Team Blacksheep Discovery Quadcopter
#
# Anton Babushkin <anton.babushkin@me.com>, Simon Wilks <sjwilks@gmail.com>, Thomas Gubler <thomasgubler@gmail.com>
# Anton Babushkin <anton@px4.io>, Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.mc_defaults

2
ROMFS/px4fmu_common/init.d/10016_3dr_iris

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# 3DR Iris Quadcopter
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

3
ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d

@ -2,8 +2,7 @@ @@ -2,8 +2,7 @@
#
# Steadidrone QU4D
#
# Thomas Gubler <thomasgubler@gmail.com>
# Lorenz Meier <lm@inf.ethz.ch>
# Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.mc_defaults

2
ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# HIL Quadcopter X
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

2
ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# HIL Quadcopter +
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

4
ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil

@ -2,13 +2,11 @@ @@ -2,13 +2,11 @@
#
# HIL Rascal 110 (Flightgear)
#
# Thomas Gubler <thomasgubler@gmail.com>
# Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.fw_defaults
echo "HIL Rascal 110 starting.."
set HIL yes
set MIXER FMU_AERT

2
ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# HIL Malolo 1 (Flightgear)
#
# Thomas Gubler <thomasgubler@gmail.com>
# Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.fw_defaults

4
ROMFS/px4fmu_common/init.d/11001_hexa_cox

@ -2,12 +2,12 @@ @@ -2,12 +2,12 @@
#
# Generic 10" Hexa coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
# Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_cox
# We only can run one channel group with one rate, so set all 8 channels
# Need to set all 8 channels
set PWM_OUTPUTS 12345678

2
ROMFS/px4fmu_common/init.d/12001_octo_cox

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Generic 10" Octo coaxial geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
# Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults

4
ROMFS/px4fmu_common/init.d/3031_phantom

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Phantom FPV Flying Wing
#
# Simon Wilks <sjwilks@gmail.com>, Thomas Gubler <thomasgubler@gmail.com>
# Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@ -21,8 +21,6 @@ then @@ -21,8 +21,6 @@ then
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 50
param set FW_P_LIM_MIN -50
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1
param set FW_RR_FF 0.5
param set FW_RR_I 0.02

6
ROMFS/px4fmu_common/init.d/3032_skywalker_x5

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Skywalker X5 Flying Wing
#
# Thomas Gubler <thomasgubler@gmail.com>, Julian Oes <joes@student.ethz.ch>
# Thomas Gubler <thomas@px4.io>, Julian Oes <julian@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@ -19,10 +19,6 @@ then @@ -19,10 +19,6 @@ then
param set FW_PR_I 0
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 1
param set FW_RR_FF 0.3
param set FW_RR_I 0

2
ROMFS/px4fmu_common/init.d/3033_wingwing

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Wing Wing (aka Z-84) Flying Wing
#
# Simon Wilks <sjwilks@gmail.com>
# Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults

2
ROMFS/px4fmu_common/init.d/3034_fx79

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# FX-79 Buffalo Flying Wing
#
# Simon Wilks <sjwilks@gmail.com>
# Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults

2
ROMFS/px4fmu_common/init.d/3035_viper

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Viper
#
# Simon Wilks <sjwilks@gmail.com>
# Simon Wilks <simon@px4.io>
#
sh /etc/init.d/rc.fw_defaults

8
ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
#!nsh
#
# TBS Caipirinha Flying Wing
# TBS Caipirinha
#
# Thomas Gubler <thomasgubler@gmail.com>
# Thomas Gubler <thomas@px4.io>
#
sh /etc/init.d/rc.fw_defaults
@ -22,10 +22,6 @@ then @@ -22,10 +22,6 @@ then
param set FW_PR_I 0
param set FW_PR_IMAX 0.2
param set FW_PR_P 0.03
param set FW_P_LIM_MAX 45
param set FW_P_LIM_MIN -45
param set FW_P_RMAX_NEG 0
param set FW_P_RMAX_POS 0
param set FW_P_ROLLFF 0
param set FW_RR_FF 0.3
param set FW_RR_I 0

2
ROMFS/px4fmu_common/init.d/4001_quad_x

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Generic 10" Quad X geometry
#
# Lorenz Meier <lm@inf.ethz.ch>
# Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/rc.mc_defaults

3
ROMFS/px4fmu_common/init.d/4008_ardrone

@ -3,9 +3,6 @@ @@ -3,9 +3,6 @@
# ARDrone
#
echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board"
# Just use the default multicopter settings.
sh /etc/init.d/rc.mc_defaults
#

4
ROMFS/px4fmu_common/init.d/4010_dji_f330

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
#!nsh
#
# DJI Flame Wheel F330 Quadcopter
# DJI Flame Wheel F330
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/4001_quad_x

4
ROMFS/px4fmu_common/init.d/4011_dji_f450

@ -1,8 +1,8 @@ @@ -1,8 +1,8 @@
#!nsh
#
# DJI Flame Wheel F450 Quadcopter
# DJI Flame Wheel F450
#
# Lorenz Meier <lm@inf.ethz.ch>
# Lorenz Meier <lorenz@px4.io>
#
sh /etc/init.d/4001_quad_x

2
ROMFS/px4fmu_common/init.d/4012_quad_x_can

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# F450-sized quadrotor with CAN
#
# Lorenz Meier <lm@inf.ethz.ch>
# Pavel Kirienko <pavel@px4.io>
#
sh /etc/init.d/4001_quad_x

2
ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb

@ -3,7 +3,7 @@ @@ -3,7 +3,7 @@
# Hobbyking Micro Integrated PCB Quadcopter
# with SimonK ESC firmware and Mystery A1510 motors
#
# Thomas Gubler <thomasgubler@gmail.com>
# Thomas Gubler <thomas@px4.io>
#
echo "HK Micro PCB Quad"

2
ROMFS/px4fmu_common/init.d/5001_quad_+

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Generic 10" Quad + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

4
ROMFS/px4fmu_common/init.d/6001_hexa_x

@ -2,12 +2,12 @@ @@ -2,12 +2,12 @@
#
# Generic 10" Hexa X geometry
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_x
# We only can run one channel group with one rate, so set all 8 channels
# Need to set all 8 channels
set PWM_OUTPUTS 12345678

4
ROMFS/px4fmu_common/init.d/7001_hexa_+

@ -2,12 +2,12 @@ @@ -2,12 +2,12 @@
#
# Generic 10" Hexa + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults
set MIXER FMU_hexa_+
# We only can run one channel group with one rate, so set all 8 channels
# Need to set all 8 channels
set PWM_OUTPUTS 12345678

2
ROMFS/px4fmu_common/init.d/8001_octo_x

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Generic 10" Octo X geometry
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

2
ROMFS/px4fmu_common/init.d/9001_octo_+

@ -2,7 +2,7 @@ @@ -2,7 +2,7 @@
#
# Generic 10" Octo + geometry
#
# Anton Babushkin <anton.babushkin@me.com>
# Anton Babushkin <anton@px4.io>
#
sh /etc/init.d/rc.mc_defaults

5
ROMFS/px4fmu_common/init.d/rc.autostart

@ -1,5 +1,4 @@ @@ -1,5 +1,4 @@
#
# Check if auto-setup from one of the standard scripts is wanted
# SYS_AUTOSTART = 0 means no autostart (default)
#
# AUTOSTART PARTITION:
@ -18,7 +17,7 @@ @@ -18,7 +17,7 @@
# 12000 .. 12999 Octo Cox
#
# Simulation setups
# Simulation
#
if param compare SYS_AUTOSTART 901
@ -53,7 +52,7 @@ then @@ -53,7 +52,7 @@ then
fi
#
# Standard plane
# Plane
#
if param compare SYS_AUTOSTART 2100 100

7
ROMFS/px4fmu_common/init.d/rc.sensors

@ -54,7 +54,6 @@ then @@ -54,7 +54,6 @@ then
fi
fi
# Start airspeed sensors
if meas_airspeed start
then
echo "[init] Using MEAS airspeed sensor"
@ -68,16 +67,12 @@ else @@ -68,16 +67,12 @@ else
fi
fi
# Check for flow sensor
if px4flow start
then
fi
#
# Start the sensor collection task.
# IMPORTANT: this also loads param offsets
# ALWAYS start this task before the
# preflight_check.
# Start sensors -> preflight_check
#
if sensors start
then

24
ROMFS/px4fmu_common/init.d/rcS

@ -137,9 +137,7 @@ then @@ -137,9 +137,7 @@ then
#
if param compare SYS_AUTOCONFIG 1
then
# We can't be sure the defaults haven't changed, so
# if someone requests a re-configuration, we do it
# cleanly from scratch (except autostart / autoconfig)
# Wipe out params
param reset_nostart
set DO_AUTOCONFIG yes
else
@ -202,12 +200,10 @@ then @@ -202,12 +200,10 @@ then
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK"
echo "PX4IO CRC OK" >> $LOG_FILE
set IO_PRESENT yes
else
echo "[init] Trying to update"
echo "PX4IO Trying to update" >> $LOG_FILE
tone_alarm MLL32CP8MB
@ -217,18 +213,15 @@ then @@ -217,18 +213,15 @@ then
usleep 500000
if px4io checkcrc $IO_FILE
then
echo "[init] PX4IO CRC OK, update successful"
echo "PX4IO CRC OK after updating" >> $LOG_FILE
tone_alarm MLL8CDE
set IO_PRESENT yes
else
echo "[init] ERROR: PX4IO update failed"
echo "PX4IO update failed" >> $LOG_FILE
tone_alarm $TUNE_OUT_ERROR
fi
else
echo "[init] ERROR: PX4IO update failed"
echo "PX4IO update failed" >> $LOG_FILE
tone_alarm $TUNE_OUT_ERROR
fi
@ -281,16 +274,12 @@ then @@ -281,16 +274,12 @@ then
fi
fi
#
# Start the datamanager (and do not abort boot if it fails)
#
# waypoint storage
if dataman start
then
fi
#
# Start the Commander (needs to be this early for in-air-restarts)
#
# Needs to be this early for in-air-restarts
commander start
#
@ -424,9 +413,6 @@ then @@ -424,9 +413,6 @@ then
fi
fi
#
# MAVLink
#
if [ $MAVLINK_FLAGS == default ]
then
# Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s
@ -454,10 +440,6 @@ then @@ -454,10 +440,6 @@ then
# Sensors, Logging, GPS
#
sh /etc/init.d/rc.sensors
#
# Start logging in all modes, including HIL
#
sh /etc/init.d/rc.logging
if [ $GPS == yes ]

109
src/modules/systemlib/mcu_version.c

@ -0,0 +1,109 @@ @@ -0,0 +1,109 @@
/****************************************************************************
*
* Copyright (c) 2014 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 mcu_version.c
*
* Read out the microcontroller version from the board
*
* @author Lorenz Meier <lorenz@px4.io>
*
*/
#include "mcu_version.h"
#include <nuttx/config.h>
#ifdef CONFIG_ARCH_CHIP_STM32
#include <up_arch.h>
#define DBGMCU_IDCODE 0xE0042000
#define STM32F40x_41x 0x413
#define STM32F42x_43x 0x419
#define REVID_MASK 0xFFFF0000
#define DEVID_MASK 0xFFF
#endif
int mcu_version(char* rev, char** revstr)
{
#ifdef CONFIG_ARCH_CHIP_STM32
uint32_t abc = getreg32(DBGMCU_IDCODE);
int32_t chip_version = abc & DEVID_MASK;
enum MCU_REV revid = (abc & REVID_MASK) >> 16;
switch (chip_version) {
case STM32F40x_41x:
*revstr = "STM32F40x";
break;
case STM32F42x_43x:
*revstr = "STM32F42x";
break;
default:
*revstr = "STM32F???";
break;
}
switch (revid) {
case MCU_REV_STM32F4_REV_A:
*rev = 'A';
break;
case MCU_REV_STM32F4_REV_Z:
*rev = 'Z';
break;
case MCU_REV_STM32F4_REV_Y:
*rev = 'Y';
break;
case MCU_REV_STM32F4_REV_1:
*rev = '1';
break;
case MCU_REV_STM32F4_REV_3:
*rev = '3';
break;
default:
*rev = '?';
revid = -1;
break;
}
return revid;
#else
return -1;
#endif
}

52
src/modules/systemlib/mcu_version.h

@ -0,0 +1,52 @@ @@ -0,0 +1,52 @@
/****************************************************************************
*
* Copyright (c) 2014 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.
*
****************************************************************************/
#pragma once
/* magic numbers from reference manual */
enum MCU_REV {
MCU_REV_STM32F4_REV_A = 0x1000,
MCU_REV_STM32F4_REV_Z = 0x1001,
MCU_REV_STM32F4_REV_Y = 0x1003,
MCU_REV_STM32F4_REV_1 = 0x1007,
MCU_REV_STM32F4_REV_3 = 0x2001
};
/**
* Reports the microcontroller version of the main CPU.
*
* @param rev The silicon revision character
* @param revstr The full chip name string
* @return The silicon revision / version number as integer
*/
__EXPORT int mcu_version(char* rev, char** revstr);

3
src/modules/systemlib/module.mk

@ -53,6 +53,7 @@ SRCS = err.c \ @@ -53,6 +53,7 @@ SRCS = err.c \
otp.c \
board_serial.c \
pwm_limit/pwm_limit.c \
circuit_breaker.c
circuit_breaker.c \
mcu_version.c
MAXOPTIMIZATION = -Os

90
src/systemcmds/ver/ver.c

@ -44,6 +44,7 @@ @@ -44,6 +44,7 @@
#include <string.h>
#include <version/version.h>
#include <systemlib/err.h>
#include <systemlib/mcu_version.h>
// string constants for version commands
static const char sz_ver_hw_str[] = "hw";
@ -52,32 +53,8 @@ static const char sz_ver_git_str[] = "git"; @@ -52,32 +53,8 @@ static const char sz_ver_git_str[] = "git";
static const char sz_ver_bdate_str[] = "bdate";
static const char sz_ver_gcc_str[] = "gcc";
static const char sz_ver_all_str[] = "all";
#ifdef CONFIG_ARCH_CHIP_STM32
#include <up_arch.h>
static const char mcu_ver_str[] = "mcu";
#define DBGMCU_IDCODE 0xE0042000
#define STM32F40x_41x 0x413
#define STM32F42x_43x 0x419
#define REVID_MASK 0xFFFF0000
#define DEVID_MASK 0xFFF
/* magic numbers from reference manual */
enum STM32F4_REV {
STM32F4_REV_A = 0x1000,
STM32F4_REV_Z = 0x1001,
STM32F4_REV_Y = 0x1003,
STM32F4_REV_1 = 0x1007,
STM32F4_REV_3 = 0x2001
};
#else
#error stm32
#endif
static void usage(const char *reason)
{
if (reason != NULL) {
@ -132,63 +109,28 @@ int ver_main(int argc, char *argv[]) @@ -132,63 +109,28 @@ int ver_main(int argc, char *argv[])
printf("GCC toolchain: %s\n", __VERSION__);
ret = 0;
#ifdef CONFIG_ARCH_CHIP_STM32
} else if (!strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) {
uint32_t abc = getreg32(DBGMCU_IDCODE);
uint32_t chip_version = abc & DEVID_MASK;
enum STM32F4_REV revid = (abc & REVID_MASK) >> 16;
printf("CHIP TYPE: ");
switch (revid) {
case STM32F40x_41x:
printf("STM32F40x");
break;
case STM32F42x_43x:
printf("STM32F42x");
break;
default:
printf("STM32F???");
break;
}
char rev;
char* revstr;
switch (chip_version) {
case STM32F4_REV_A:
rev = 'A';
break;
case STM32F4_REV_Z:
rev = 'Z';
break;
case STM32F4_REV_Y:
rev = 'Y';
break;
case STM32F4_REV_1:
rev = '1';
break;
case STM32F4_REV_3:
rev = '3';
break;
default:
rev = '?';
break;
}
int chip_version = mcu_version(&rev, &revstr);
if (chip_version < 0) {
printf("UNKNOWN MCU");
ret = 1;
printf("\nHW REV: %c\n", rev);
} else {
printf("MCU: %s, rev. %c\n", revstr, rev);
if (rev < STM32F4_REV_3) {
printf("\n\nWARNING WARNING WARNING!\n"
"Revision %c has a silicon errata\n"
"on USB connectivity combined with\n"
"flash bank #2. This device can only\n"
"utilize a maximum of 1MB flash safely!\n"
"http://px4.io/help/errata\n", rev);
if (chip_version < MCU_REV_STM32F4_REV_3) {
printf("\n\nWARNING WARNING WARNING!\n"
"Revision %c has a silicon errata\n"
"This device can only utilize a maximum of 1MB flash safely!\n"
"http://px4.io/help/errata\n", rev);
}
}
ret = 0;
#endif
} else {
errx(1, "unknown command.\n");

Loading…
Cancel
Save