Skip to content

Commit

Permalink
Enabled warnings used for FMU.
Browse files Browse the repository at this point in the history
  • Loading branch information
jgoppert committed Jan 23, 2015
1 parent 9062d2c commit 61875fc
Show file tree
Hide file tree
Showing 17 changed files with 222 additions and 65 deletions.
189 changes: 154 additions & 35 deletions CMakeLists.txt
@@ -1,41 +1,44 @@
cmake_minimum_required(VERSION 2.8)
option(HOST_TEST "do host based testing (no cross-compiling)" OFF)

# toolchain
#-----------------------------------------------------
option(HOST_TEST "do host based testing (no cross-compiling)" OFF)
if (NOT HOST_TEST)
set(CMAKE_TOOLCHAIN_FILE cmake/Toolchain-arm-none-eabi.cmake)
endif()

project(px4flow C ASM)

# config
#-----------------------------------------------------
set(JTAGCONFIG ${CMAKE_SOURCE_DIR}/olimex-jtag-tiny.cfg)
#set(JTAGCONFIG ${CMAKE_SOURCE_DIR}/olimex-arm-usb-tiny-h.cfg)
#set(JTAGCONFIG ${CMAKE_SOURCE_DIR}/olimex-arm-usb-tiny-h.cfg)
set(BOARDCONFIG ${CMAKE_SOURCE_DIR}/stm32f4x.cfg)

# dependencies/ programs
#-----------------------------------------------------
find_program(OPENOCD openocd HINT ../../sat/bin/)

# testing
#-----------------------------------------------------
enable_testing()

# packaging
#-----------------------------------------------------
set(CPACK_PACKAGE_CONTACT "px4users@googlegroups.com")
set(CPACK_INCLUDE_TOPLEVEL_DIRECTORY 0)
set(CPACK_PACKAGE_VERSION_MAJOR "0")
set(CPACK_PACKAGE_VERSION_MINOR "0")
set(CPACK_PACKAGE_VERSION_PATCH "0")
include(CPack)

message(STATUS "building for: ${CMAKE_SYSTEM_NAME}")

if (${CMAKE_SYSTEM_NAME} STREQUAL "Arm")
# and linker script if compiling for board
foreach(ARG in EXE TEST)
set(CMAKE_${ARG}_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -T${CMAKE_SOURCE_DIR}/stm32f4.ld")
endforeach()
set(COMMON_FLAGS "-mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -Wall -Wextra -MD")
else()
set(COMMON_FLAGS "")
endif()
set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${COMMON_FLAGS} --std=gnu99 -Wall")
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${COMMON_FLAGS}")
add_definitions(-DMAVLINK_SEND_UART_BYTES=mavlink_send_uart_bytes)
# functions
#-----------------------------------------------------
function(join VARNAME)
string (REGEX REPLACE "([^\\]|^);" "\\1 " _TMP_STR "${${VARNAME}}")
string (REGEX REPLACE "[\\](.)" "\\1" _TMP_STR "${_TMP_STR}") #fixes escaping
set(${VARNAME} "${_TMP_STR}" PARENT_SCOPE)
endfunction()

macro(generate_firmware NAME)
add_custom_target(firmware_${NAME} ALL DEPENDS ${NAME}.px4)
Expand All @@ -46,6 +49,103 @@ macro(generate_firmware NAME)
DEPENDS ${NAME})
endmacro()

# flags
#-----------------------------------------------------
if (${CMAKE_SYSTEM_NAME} STREQUAL "Arm")
# board CORTEXM44
set(CPU_FLAGS
-mcpu=cortex-m4
-mthumb
-march=armv7e-m
-mfpu=fpv4-sp-d16
-mfloat-abi=hard
)
else()
set(CPU_FLAGS)
endif()
set(OPT_FLAGS
-O3
-g
-fno-strict-aliasing
-fno-strength-reduce
-fomit-frame-pointer
-funsafe-math-optimizations
-fno-builtin-printf
-ffunction-sections
-fdata-sections
)
set(C_FLAGS
-std=gnu99
-fno-common
)
set(CXX_FLAGS
-fno-exceptions
-fno-rtti
-std=gnu++0x
-fno-threadsafe-statics
)
set(WARNINGS
-Wall
-Wextra
-Wdouble-promotion
-Wshadow
-Wfloat-equal
-Wframe-larger-than=1024
-Wpointer-arith
-Wlogical-op
-Wmissing-declarations
-Wpacked
-Wno-unused-parameter
-Werror=format-security
-Werror=array-bounds
-Wfatal-errors
-Wformat=1
-Werror=unused-but-set-variable
-Werror=unused-variable
-Werror=double-promotion
-Werror=reorder
#-Wcast-qual - generates spurious noreturn attribute warnings, try again later
#-Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
#-Wcast-align - would help catch bad casts in some cases, but generates too many false positives
)
set(C_WARNINGS
-Wbad-function-cast
-Wstrict-prototypes
-Wold-style-declaration
-Wmissing-parameter-type
-Wmissing-prototypes
-Wnested-externs
)
set(CXX_WARNINGS
-Wno-missing-field-initializers
)
set(LD_FLAGS
-Wl,--warn-common
-Wl,--gc-sections
)
set(CMAKE_C_FLAGS
${CPU_FLAGS}
${C_FLAGS}
${WARNINGS}
${C_WARNINGS}
${OPT_FLAGS}
)
join(CMAKE_C_FLAGS)
set(CMAKE_CXX_FLAGS
${CPU_FLAGS}
${CXX_FLAGS}
${WARNINGS}
${CXX_WARNINGS}
${OPT_FLAGS}
)
join(CMAKE_CXX_FLAGS)
set(CMAKE_EXE_LINKER_FLAGS ${LD_FLAGS})
join(CMAKE_EXE_LINKER_FLAGS)

message(STATUS "cflags: ${CMAKE_C_FLAGS}")

add_definitions(-DMAVLINK_SEND_UART_BYTES=mavlink_send_uart_bytes)

include_directories(
inc lib
lib/STM32F4xx_StdPeriph_Driver/inc
Expand All @@ -59,6 +159,27 @@ include_directories(

# source
#-----------------------------------------------------
set(PERIPH_SRC
lib/startup_stm32f4xx.s
lib/STM32F4xx_StdPeriph_Driver/src/misc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c
lib/STM32_USB_OTG_Driver/src/usb_core.c
lib/STM32_USB_OTG_Driver/src/usb_dcd_int.c
lib/STM32_USB_OTG_Driver/src/usb_dcd.c
lib/STM32_USB_Device_Library/Core/src/usbd_core.c
lib/STM32_USB_Device_Library/Core/src/usbd_req.c
lib/STM32_USB_Device_Library/Core/src/usbd_ioreq.c
lib/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c
)

set(PX4FLOW_HDRS
inc/communication.h
inc/dcmi.h
Expand All @@ -83,25 +204,8 @@ set(PX4FLOW_HDRS
inc/usbd_desc.h
inc/utils.h
)

set(PX4FLOW_SRC
lib/startup_stm32f4xx.s
lib/STM32F4xx_StdPeriph_Driver/src/misc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_rcc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dma.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_dcmi.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_i2c.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_tim.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_spi.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_usart.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_adc.c
lib/STM32F4xx_StdPeriph_Driver/src/stm32f4xx_gpio.c
lib/STM32_USB_OTG_Driver/src/usb_core.c
lib/STM32_USB_OTG_Driver/src/usb_dcd_int.c
lib/STM32_USB_OTG_Driver/src/usb_dcd.c
lib/STM32_USB_Device_Library/Core/src/usbd_core.c
lib/STM32_USB_Device_Library/Core/src/usbd_req.c
lib/STM32_USB_Device_Library/Core/src/usbd_ioreq.c
lib/STM32_USB_Device_Library/Class/cdc/src/usbd_cdc_core.c
src/communication.c
src/dcmi.c
src/debug.c
Expand Down Expand Up @@ -130,9 +234,21 @@ set(PX4FLOW_SRC
# building
#-----------------------------------------------------
if (${CMAKE_SYSTEM_NAME} STREQUAL "Arm")

# periph lib
add_library(periph STATIC ${PERIPH_SRC})
set_target_properties(periph PROPERTIES
LINK_FLAGS ""
#COMPILE_FLAGS "-Werror"
)

# board executable
add_executable(px4flow ${PX4FLOW_SRC} ${PX4FLOW_HDRS})
target_link_libraries(px4flow nosys m)
target_link_libraries(px4flow periph nosys m)
set_target_properties(px4flow PROPERTIES
LINK_FLAGS "-T${CMAKE_SOURCE_DIR}/stm32f4.ld"
#COMPILE_FLAGS "-Werror"
)
generate_firmware(px4flow)
else()
# host based testing
Expand All @@ -142,6 +258,9 @@ else()
inc/sonar_mode_filter.h
unittests/tests.c
)
#set_target_properties(sonar_mode_filter PROPERTIES
# COMPILE_FLAGS "-Werror"
#)
add_test(sonar_mode_filter sonar_mode_filter)
endif()

Expand Down
6 changes: 3 additions & 3 deletions inc/gyro.h
Expand Up @@ -151,13 +151,13 @@ void gyro_read(float* x_rate, float* y_rate, float* z_rate, int16_t* gyro_temp);

/* Low layer functions */
void spi_config(void);
void l3gd20_config();
void l3gd20_config(void);
uint8_t l3gd20_ReadByte(void);
uint8_t l3gd20_SendByte(uint8_t byte);
uint16_t l3gd20_SendHalfWord(uint16_t HalfWord);
void l3gd20_WriteEnable(void);
void l3gd20_WaitForWriteEnd(void);
uint8_t getGyroRange();
int getGyroScalingFactor();
uint8_t getGyroRange(void);
int getGyroScalingFactor(void);

#endif /* SPI_L3GD20_H_ */
4 changes: 2 additions & 2 deletions inc/i2c.h
Expand Up @@ -37,9 +37,9 @@
* @brief Configures I2C1 for communication as a slave (default behaviour for STM32F)
*/

void i2c_init();
void i2c_init(void);
void update_TX_buffer(float pixel_flow_x, float pixel_flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t qual,
float ground_distance, float x_rate, float y_rate, float z_rate, int16_t gyro_temp);
char i2c_get_ownaddress1();
char i2c_get_ownaddress1(void);
#endif /* I2C_H_ */

8 changes: 5 additions & 3 deletions inc/settings.h
Expand Up @@ -98,7 +98,7 @@ typedef struct

} SysState_TypeDef;

enum
enum global_param_id_t
{
PARAM_SYSTEM_ID = 0,
PARAM_COMPONENT_ID,
Expand Down Expand Up @@ -146,7 +146,7 @@ enum

ONBOARD_PARAM_COUNT

} global_param_id;
};

struct global_struct
{
Expand All @@ -157,7 +157,9 @@ struct global_struct

};

struct global_struct global_data;
/* global declarations */
extern enum global_param_id_t global_param_id;
extern struct global_struct global_data;

/******************************************************************
* ALL SETTINGS FUNCTIONS
Expand Down
4 changes: 2 additions & 2 deletions inc/sonar.h
Expand Up @@ -63,11 +63,11 @@ bool sonar_read(float* sonar_value_filtered, float* sonar_value_raw);
/**
* @brief Get the timestamp of the new sonar value when available to the main code
*/
uint32_t get_sonar_measure_time();
uint32_t get_sonar_measure_time(void);

/**
* @brief Get the timestamp of the new sonar value when the interrupt is triggered
*/
uint32_t get_sonar_measure_time_interrupt();
uint32_t get_sonar_measure_time_interrupt(void);

#endif /* SONAR_H_ */
2 changes: 1 addition & 1 deletion inc/usart.h
Expand Up @@ -39,7 +39,7 @@
/**
* @brief Configures USART2 and USART3 for communication
*/
void usart_init();
void usart_init(void);

/**
* @brief Pop one byte from ringbuffer of USART2
Expand Down
4 changes: 2 additions & 2 deletions src/communication.c
Expand Up @@ -47,8 +47,8 @@
#include "debug.h"
#include "communication.h"

extern uint32_t get_boot_time_us();
extern void buffer_reset();
extern uint32_t get_boot_time_us(void);
extern void buffer_reset(void);
extern void systemreset(bool to_bootloader);

mavlink_system_t mavlink_system;
Expand Down
2 changes: 2 additions & 0 deletions src/flow.c
Expand Up @@ -55,6 +55,8 @@

#define sign(x) (( x > 0 ) - ( x < 0 ))

uint8_t compute_flow(uint8_t *image1, uint8_t *image2, float x_rate, float y_rate, float z_rate, float *pixel_flow_x, float *pixel_flow_y);

// compliments of Adam Williams
#define ABSDIFF(frame1, frame2) \
({ \
Expand Down
9 changes: 7 additions & 2 deletions src/i2c.c
Expand Up @@ -44,6 +44,11 @@
#include "mavlink_bridge_header.h"
#include <mavlink.h>

/* prototypes */
void I2C1_EV_IRQHandler(void);
void I2C1_ER_IRQHandler(void);
char readI2CAddressOffset(void);

static char offset = 0;
uint8_t dataRX = 0;
uint8_t txDataFrame1[2][I2C_FRAME_SIZE];
Expand Down Expand Up @@ -337,7 +342,7 @@ void update_TX_buffer(float pixel_flow_x, float pixel_flow_y,

}

char readI2CAddressOffset() {
char readI2CAddressOffset(void) {
//read 3bit address offset of 7 bit address
offset = 0x00;
offset = GPIO_ReadInputData(GPIOC ) >> 13; //bit 0
Expand All @@ -347,6 +352,6 @@ char readI2CAddressOffset() {
return offset;
}

char i2c_get_ownaddress1() {
char i2c_get_ownaddress1(void) {
return (I2C1_OWNADDRESS_1_BASE + readI2CAddressOffset()) << 1; //add offset to base and shift 1 bit to generate valid 7 bit address
}
5 changes: 5 additions & 0 deletions src/main.c
Expand Up @@ -68,6 +68,11 @@
#define SCB_CPACR (*((uint32_t*) (((0xE000E000UL) + 0x0D00UL) + 0x088)))
#endif


/* prototypes */
void delay(unsigned msec);
void buffer_reset(void);

__ALIGN_BEGIN USB_OTG_CORE_HANDLE USB_OTG_dev __ALIGN_END;

/* fast image buffers for calculations */
Expand Down

0 comments on commit 61875fc

Please sign in to comment.