forked from Archive/PX4-Autopilot
Merge remote-tracking branch 'upstream/master' into dev_ros
Conflicts: .gitmodules
This commit is contained in:
commit
f4e0dc2857
|
@ -13,3 +13,6 @@
|
|||
[submodule "Tools/gencpp"]
|
||||
path = Tools/gencpp
|
||||
url = https://github.com/ros/gencpp.git
|
||||
[submodule "unittests/gtest"]
|
||||
path = unittests/gtest
|
||||
url = https://github.com/sjwilks/gtest.git
|
||||
|
|
12
Makefile
12
Makefile
|
@ -261,14 +261,16 @@ tests:
|
|||
#
|
||||
.PHONY: clean
|
||||
clean:
|
||||
$(Q) $(RMDIR) $(BUILD_DIR)*.build > /dev/null
|
||||
$(Q) $(REMOVE) $(IMAGE_DIR)*.px4 > /dev/null
|
||||
@echo > /dev/null
|
||||
$(Q) $(RMDIR) $(BUILD_DIR)*.build
|
||||
$(Q) $(REMOVE) $(IMAGE_DIR)*.px4
|
||||
|
||||
.PHONY: distclean
|
||||
distclean: clean
|
||||
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export > /dev/null
|
||||
$(Q) $(MAKE) -C $(NUTTX_SRC) -r $(MQUIET) distclean > /dev/null
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && $(FIND) . -maxdepth 1 -type l -delete) > /dev/null
|
||||
@echo > /dev/null
|
||||
$(Q) $(REMOVE) $(ARCHIVE_DIR)*.export
|
||||
$(Q) $(MAKE) -C $(NUTTX_SRC) -r $(MQUIET) distclean
|
||||
$(Q) (cd $(NUTTX_SRC)/configs && $(FIND) . -maxdepth 1 -type l -delete)
|
||||
|
||||
#
|
||||
# Print some help text
|
||||
|
|
2
NuttX
2
NuttX
|
@ -1 +1 @@
|
|||
Subproject commit b66de6506941dc7628efcf65e5543c0e3cb05a8f
|
||||
Subproject commit 3c36467c0d5572431a09ae50013328a4693ee070
|
|
@ -56,7 +56,6 @@ fi
|
|||
|
||||
if meas_airspeed start
|
||||
then
|
||||
echo "[i] Using MEAS airspeed sensor"
|
||||
else
|
||||
if ets_airspeed start
|
||||
then
|
||||
|
@ -67,6 +66,7 @@ else
|
|||
fi
|
||||
fi
|
||||
|
||||
# Check for flow sensor
|
||||
if px4flow start
|
||||
then
|
||||
fi
|
||||
|
|
|
@ -25,6 +25,7 @@ mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20
|
|||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s POSITION_TARGET_GLOBAL_INT -r 10
|
||||
usleep 100000
|
||||
mavlink stream -d /dev/ttyACM0 -s LOCAL_POSITION_NED -r 30
|
||||
|
||||
# Exit shell to make it available to MAVLink
|
||||
exit
|
||||
|
|
|
@ -430,6 +430,16 @@ then
|
|||
unset MAVLINK_F
|
||||
|
||||
#
|
||||
# MAVLink onboard / TELEM2
|
||||
#
|
||||
if ver hwcmp PX4FMU_V2
|
||||
then
|
||||
if param compare SYS_COMPANION 921600
|
||||
then
|
||||
mavlink start -d /dev/ttyS2 -b 921600 -m onboard
|
||||
fi
|
||||
fi
|
||||
|
||||
# UAVCAN
|
||||
#
|
||||
sh /etc/init.d/rc.uavcan
|
||||
|
|
|
@ -32,6 +32,7 @@ MODULES += drivers/ll40ls
|
|||
# MODULES += drivers/trone
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/hott
|
||||
MODULES += drivers/hott/hott_telemetry
|
||||
MODULES += drivers/hott/hott_sensors
|
||||
# MODULES += drivers/blinkm
|
||||
|
|
|
@ -127,6 +127,7 @@ ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics
|
|||
#
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wextra \
|
||||
-Werror \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
-Wfloat-equal \
|
||||
|
|
|
@ -119,6 +119,7 @@ endif
|
|||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wno-sign-compare \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
|
|
|
@ -119,6 +119,7 @@ endif
|
|||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wno-sign-compare \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
|
|
|
@ -404,7 +404,7 @@ CONFIG_SIG_SIGWORK=4
|
|||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=38
|
||||
CONFIG_NFILE_DESCRIPTORS=42
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
|
|
|
@ -119,6 +119,7 @@ endif
|
|||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=c++11
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wno-sign-compare \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
|
|
|
@ -438,7 +438,7 @@ CONFIG_SIG_SIGWORK=4
|
|||
CONFIG_MAX_TASKS=32
|
||||
CONFIG_MAX_TASK_ARGS=10
|
||||
CONFIG_NPTHREAD_KEYS=4
|
||||
CONFIG_NFILE_DESCRIPTORS=38
|
||||
CONFIG_NFILE_DESCRIPTORS=42
|
||||
CONFIG_NFILE_STREAMS=8
|
||||
CONFIG_NAME_MAX=32
|
||||
CONFIG_PREALLOC_MQ_MSGS=4
|
||||
|
|
|
@ -108,6 +108,7 @@ endif
|
|||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wno-sign-compare \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
|
|
|
@ -108,6 +108,7 @@ endif
|
|||
ARCHCFLAGS = -std=gnu99
|
||||
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
|
||||
ARCHWARNINGS = -Wall \
|
||||
-Wno-sign-compare \
|
||||
-Wextra \
|
||||
-Wdouble-promotion \
|
||||
-Wshadow \
|
||||
|
|
|
@ -121,7 +121,7 @@ int ardrone_interface_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 15,
|
||||
1100,
|
||||
ardrone_interface_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -45,6 +45,7 @@
|
|||
#include "board_config.h"
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
/*
|
||||
* Ideally we'd be able to get these from up_internal.h,
|
||||
|
@ -54,7 +55,7 @@
|
|||
* CONFIG_ARCH_LEDS configuration switch.
|
||||
*/
|
||||
__BEGIN_DECLS
|
||||
extern void led_init();
|
||||
extern void led_init(void);
|
||||
extern void led_on(int led);
|
||||
extern void led_off(int led);
|
||||
extern void led_toggle(int led);
|
||||
|
|
|
@ -105,6 +105,7 @@ __BEGIN_DECLS
|
|||
#define GPIO_SPI_CS_ACCEL_MAG (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
|
||||
#define GPIO_SPI_CS_BARO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
|
||||
#define GPIO_SPI_CS_FRAM (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN10)
|
||||
#define GPIO_SPI_CS_HMC (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN1)
|
||||
#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2)
|
||||
#define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
|
||||
#define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
|
||||
|
@ -119,6 +120,7 @@ __BEGIN_DECLS
|
|||
#define PX4_SPIDEV_ACCEL_MAG 2
|
||||
#define PX4_SPIDEV_BARO 3
|
||||
#define PX4_SPIDEV_MPU 4
|
||||
#define PX4_SPIDEV_HMC 5
|
||||
|
||||
/* External bus */
|
||||
#define PX4_SPIDEV_EXT0 1
|
||||
|
|
|
@ -73,6 +73,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
|
|||
stm32_configgpio(GPIO_SPI_CS_GYRO);
|
||||
stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG);
|
||||
stm32_configgpio(GPIO_SPI_CS_BARO);
|
||||
stm32_configgpio(GPIO_SPI_CS_HMC);
|
||||
stm32_configgpio(GPIO_SPI_CS_MPU);
|
||||
|
||||
/* De-activate all peripherals,
|
||||
|
@ -82,6 +83,7 @@ __EXPORT void weak_function stm32_spiinitialize(void)
|
|||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
|
||||
stm32_configgpio(GPIO_EXTI_GYRO_DRDY);
|
||||
|
@ -117,6 +119,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
|
|||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
break;
|
||||
|
||||
|
@ -125,6 +128,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
|
|||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
break;
|
||||
|
||||
|
@ -133,6 +137,16 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
|
|||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
break;
|
||||
|
||||
case PX4_SPIDEV_HMC:
|
||||
/* Making sure the other peripherals are not selected */
|
||||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, !selected);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, 1);
|
||||
break;
|
||||
|
||||
|
@ -141,6 +155,7 @@ __EXPORT void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
|
|||
stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_BARO, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_HMC, 1);
|
||||
stm32_gpiowrite(GPIO_SPI_CS_MPU, !selected);
|
||||
break;
|
||||
|
||||
|
|
|
@ -221,7 +221,7 @@ int frsky_telemetry_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT,
|
||||
2000,
|
||||
frsky_telemetry_thread_main,
|
||||
(const char **)argv);
|
||||
(char * const *)argv);
|
||||
|
||||
while (!thread_running) {
|
||||
usleep(200);
|
||||
|
|
|
@ -41,6 +41,6 @@
|
|||
#ifndef COMMS_H_
|
||||
#define COMMS_H
|
||||
|
||||
int open_uart(const char *device);
|
||||
__EXPORT int open_uart(const char *device);
|
||||
|
||||
#endif /* COMMS_H_ */
|
||||
|
|
|
@ -214,7 +214,7 @@ hott_sensors_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT,
|
||||
1024,
|
||||
hott_sensors_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -37,8 +37,6 @@
|
|||
|
||||
MODULE_COMMAND = hott_sensors
|
||||
|
||||
SRCS = hott_sensors.cpp \
|
||||
../messages.cpp \
|
||||
../comms.cpp
|
||||
SRCS = hott_sensors.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
|
@ -240,7 +240,7 @@ hott_telemetry_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT,
|
||||
2048,
|
||||
hott_telemetry_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -37,8 +37,6 @@
|
|||
|
||||
MODULE_COMMAND = hott_telemetry
|
||||
|
||||
SRCS = hott_telemetry.cpp \
|
||||
../messages.cpp \
|
||||
../comms.cpp
|
||||
SRCS = hott_telemetry.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
|
|
@ -235,15 +235,15 @@ struct gps_module_msg {
|
|||
// The maximum size of a message.
|
||||
#define MAX_MESSAGE_BUFFER_SIZE 45
|
||||
|
||||
void init_sub_messages(void);
|
||||
void init_pub_messages(void);
|
||||
void build_gam_request(uint8_t *buffer, size_t *size);
|
||||
void publish_gam_message(const uint8_t *buffer);
|
||||
void build_eam_response(uint8_t *buffer, size_t *size);
|
||||
void build_gam_response(uint8_t *buffer, size_t *size);
|
||||
void build_gps_response(uint8_t *buffer, size_t *size);
|
||||
float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
|
||||
void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
|
||||
__EXPORT void init_sub_messages(void);
|
||||
__EXPORT void init_pub_messages(void);
|
||||
__EXPORT void build_gam_request(uint8_t *buffer, size_t *size);
|
||||
__EXPORT void publish_gam_message(const uint8_t *buffer);
|
||||
__EXPORT void build_eam_response(uint8_t *buffer, size_t *size);
|
||||
__EXPORT void build_gam_response(uint8_t *buffer, size_t *size);
|
||||
__EXPORT void build_gps_response(uint8_t *buffer, size_t *size);
|
||||
__EXPORT float _get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
|
||||
__EXPORT void convert_to_degrees_minutes_seconds(double lat, int *deg, int *min, int *sec);
|
||||
|
||||
|
||||
#endif /* MESSAGES_H_ */
|
||||
|
|
|
@ -0,0 +1,41 @@
|
|||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Graupner HoTT Sensors messages.
|
||||
#
|
||||
|
||||
SRCS = messages.cpp \
|
||||
comms.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
|
@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
|
|||
SRCS = px4flow.cpp
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wno-attributes
|
||||
|
|
|
@ -106,7 +106,7 @@ struct i2c_frame {
|
|||
};
|
||||
struct i2c_frame f;
|
||||
|
||||
typedef struct i2c_integral_frame {
|
||||
struct i2c_integral_frame {
|
||||
uint16_t frame_count_since_last_readout;
|
||||
int16_t pixel_flow_x_integral;
|
||||
int16_t pixel_flow_y_integral;
|
||||
|
|
|
@ -109,7 +109,7 @@ int roboclaw_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 10,
|
||||
2048,
|
||||
roboclaw_thread_main,
|
||||
(const char **)argv);
|
||||
(char * const *)argv);
|
||||
exit(0);
|
||||
|
||||
} else if (!strcmp(argv[1], "test")) {
|
||||
|
|
|
@ -90,7 +90,9 @@ static const int ERROR = -1;
|
|||
#define SF0X_TAKE_RANGE_REG 'd'
|
||||
#define SF02F_MIN_DISTANCE 0.0f
|
||||
#define SF02F_MAX_DISTANCE 40.0f
|
||||
#define SF0X_DEFAULT_PORT "/dev/ttyS2"
|
||||
|
||||
// designated SERIAL4/5 on Pixhawk
|
||||
#define SF0X_DEFAULT_PORT "/dev/ttyS6"
|
||||
|
||||
class SF0X : public device::CDev
|
||||
{
|
||||
|
|
|
@ -206,7 +206,7 @@ static const uint8_t crc_table[] = {
|
|||
0xfa, 0xfd, 0xf4, 0xf3
|
||||
};
|
||||
|
||||
uint8_t crc8(uint8_t *p, uint8_t len){
|
||||
static uint8_t crc8(uint8_t *p, uint8_t len) {
|
||||
uint16_t i;
|
||||
uint16_t crc = 0x0;
|
||||
|
||||
|
|
|
@ -423,7 +423,7 @@ int ex_fixedwing_control_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 20,
|
||||
2048,
|
||||
fixedwing_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
thread_running = true;
|
||||
exit(0);
|
||||
}
|
||||
|
|
|
@ -41,3 +41,5 @@ SRCS = main.c \
|
|||
params.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
EXTRACFLAGS = -Wframe-larger-than=1200
|
||||
|
|
|
@ -115,7 +115,7 @@ int flow_position_estimator_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 5,
|
||||
4000,
|
||||
flow_position_estimator_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -39,3 +39,5 @@ MODULE_COMMAND = flow_position_estimator
|
|||
|
||||
SRCS = flow_position_estimator_main.c \
|
||||
flow_position_estimator_params.c
|
||||
|
||||
EXTRACFLAGS = -Wno-float-equal
|
||||
|
|
|
@ -39,13 +39,15 @@
|
|||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <nuttx/config.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/uORB.h>
|
||||
|
||||
__EXPORT int ex_hwtest_main(int argc, char *argv[]);
|
||||
|
||||
|
@ -53,7 +55,7 @@ int ex_hwtest_main(int argc, char *argv[])
|
|||
{
|
||||
warnx("DO NOT FORGET TO STOP THE COMMANDER APP!");
|
||||
warnx("(run <commander stop> to do so)");
|
||||
warnx("usage: http://px4.io/dev/examples/write_output");
|
||||
warnx("usage: http://px4.io/dev/examples/write_output");
|
||||
|
||||
struct actuator_controls_s actuators;
|
||||
memset(&actuators, 0, sizeof(actuators));
|
||||
|
|
|
@ -107,7 +107,7 @@ int matlab_csv_serial_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 5,
|
||||
2000,
|
||||
matlab_csv_serial_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -38,10 +38,13 @@
|
|||
* @author Example User <mail@example.com>
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/sched.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/err.h>
|
||||
|
@ -100,7 +103,7 @@ int px4_daemon_app_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT,
|
||||
2000,
|
||||
px4_daemon_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -181,6 +181,11 @@ rotate_3f(enum Rotation rot, float &x, float &y, float &z)
|
|||
x = tmp;
|
||||
return;
|
||||
}
|
||||
case ROTATION_ROLL_270_YAW_270: {
|
||||
tmp = z; z = -y; y = tmp;
|
||||
tmp = x; x = y; y = -tmp;
|
||||
return;
|
||||
}
|
||||
case ROTATION_PITCH_90: {
|
||||
tmp = z; z = -x; x = tmp;
|
||||
return;
|
||||
|
|
|
@ -72,7 +72,7 @@ const char *decode_states[] = {"UNSYNCED",
|
|||
#define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
|
||||
|
||||
static enum ST24_DECODE_STATE _decode_state = ST24_DECODE_STATE_UNSYNCED;
|
||||
static unsigned _rxlen;
|
||||
static uint8_t _rxlen;
|
||||
|
||||
static ReceiverFcPacket _rxpacket;
|
||||
|
||||
|
|
|
@ -63,6 +63,7 @@
|
|||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/vision_position_estimate.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <lib/mathlib/mathlib.h>
|
||||
|
@ -134,7 +135,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 5,
|
||||
7200,
|
||||
attitude_estimator_ekf_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -207,7 +208,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
}; /**< init: identity matrix */
|
||||
|
||||
float debugOutput[4] = { 0.0f };
|
||||
|
||||
int overloadcounter = 19;
|
||||
|
||||
/* Initialize filter */
|
||||
|
@ -220,6 +220,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
memset(&raw, 0, sizeof(raw));
|
||||
struct vehicle_gps_position_s gps;
|
||||
memset(&gps, 0, sizeof(gps));
|
||||
gps.eph = 100000;
|
||||
gps.epv = 100000;
|
||||
struct vehicle_global_position_s global_pos;
|
||||
memset(&global_pos, 0, sizeof(global_pos));
|
||||
struct vehicle_attitude_s att;
|
||||
|
@ -258,9 +260,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
/* subscribe to param changes */
|
||||
int sub_params = orb_subscribe(ORB_ID(parameter_update));
|
||||
|
||||
/* subscribe to control mode*/
|
||||
/* subscribe to control mode */
|
||||
int sub_control_mode = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
|
||||
/* subscribe to vision estimate */
|
||||
int vision_sub = orb_subscribe(ORB_ID(vision_position_estimate));
|
||||
|
||||
/* advertise attitude */
|
||||
orb_advert_t pub_att = orb_advertise(ORB_ID(vehicle_attitude), &att);
|
||||
|
||||
|
@ -268,14 +273,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
|
||||
thread_running = true;
|
||||
|
||||
/* advertise debug value */
|
||||
// struct debug_key_value_s dbg = { .key = "", .value = 0.0f };
|
||||
// orb_advert_t pub_dbg = -1;
|
||||
|
||||
/* keep track of sensor updates */
|
||||
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
|
||||
|
||||
struct attitude_estimator_ekf_params ekf_params = { 0 };
|
||||
struct attitude_estimator_ekf_params ekf_params;
|
||||
memset(&ekf_params, 0, sizeof(ekf_params));
|
||||
|
||||
struct attitude_estimator_ekf_param_handles ekf_param_handles = { 0 };
|
||||
|
||||
|
@ -293,6 +295,8 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
math::Matrix<3, 3> R_decl;
|
||||
R_decl.identity();
|
||||
|
||||
struct vision_position_estimate vision {};
|
||||
|
||||
/* register the perf counter */
|
||||
perf_counter_t ekf_loop_perf = perf_alloc(PC_ELAPSED, "attitude_estimator_ekf");
|
||||
|
||||
|
@ -313,8 +317,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
orb_copy(ORB_ID(vehicle_control_mode), sub_control_mode, &control_mode);
|
||||
|
||||
if (!control_mode.flag_system_hil_enabled) {
|
||||
fprintf(stderr,
|
||||
"[att ekf] WARNING: Not getting sensors - sensor app running?\n");
|
||||
warnx("WARNING: Not getting sensors - sensor app running?");
|
||||
}
|
||||
|
||||
} else {
|
||||
|
@ -449,9 +452,30 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
|||
sensor_last_timestamp[2] = raw.magnetometer_timestamp;
|
||||
}
|
||||
|
||||
z_k[6] = raw.magnetometer_ga[0];
|
||||
z_k[7] = raw.magnetometer_ga[1];
|
||||
z_k[8] = raw.magnetometer_ga[2];
|
||||
bool vision_updated = false;
|
||||
orb_check(vision_sub, &vision_updated);
|
||||
|
||||
if (vision_updated) {
|
||||
orb_copy(ORB_ID(vision_position_estimate), vision_sub, &vision);
|
||||
}
|
||||
|
||||
if (vision.timestamp_boot > 0 && (hrt_elapsed_time(&vision.timestamp_boot) < 500000)) {
|
||||
|
||||
math::Quaternion q(vision.q);
|
||||
math::Matrix<3, 3> Rvis = q.to_dcm();
|
||||
|
||||
math::Vector<3> v(1.0f, 0.0f, 0.4f);
|
||||
|
||||
math::Vector<3> vn = Rvis * v;
|
||||
|
||||
z_k[6] = vn(0);
|
||||
z_k[7] = vn(1);
|
||||
z_k[8] = vn(2);
|
||||
} else {
|
||||
z_k[6] = raw.magnetometer_ga[0];
|
||||
z_k[7] = raw.magnetometer_ga[1];
|
||||
z_k[8] = raw.magnetometer_ga[2];
|
||||
}
|
||||
|
||||
uint64_t now = hrt_absolute_time();
|
||||
unsigned int time_elapsed = now - last_run;
|
||||
|
|
|
@ -42,3 +42,7 @@ SRCS = attitude_estimator_ekf_main.cpp \
|
|||
codegen/AttitudeEKF.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
EXTRACFLAGS = -Wno-float-equal -Wframe-larger-than=3600
|
||||
|
||||
EXTRACXXFLAGS = -Wframe-larger-than=2400
|
||||
|
|
|
@ -153,7 +153,7 @@ int attitude_estimator_so3_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 5,
|
||||
14000,
|
||||
attitude_estimator_so3_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -8,3 +8,5 @@ SRCS = attitude_estimator_so3_main.cpp \
|
|||
attitude_estimator_so3_params.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
EXTRACXXFLAGS = -Wno-float-equal
|
||||
|
|
|
@ -524,6 +524,9 @@ BottleDrop::task_main()
|
|||
}
|
||||
|
||||
switch (_drop_state) {
|
||||
case DROP_STATE_INIT:
|
||||
// do nothing
|
||||
break;
|
||||
|
||||
case DROP_STATE_TARGET_VALID:
|
||||
{
|
||||
|
@ -690,6 +693,10 @@ BottleDrop::task_main()
|
|||
orb_publish(ORB_ID(onboard_mission), _onboard_mission_pub, &_onboard_mission);
|
||||
}
|
||||
break;
|
||||
|
||||
case DROP_STATE_BAY_CLOSED:
|
||||
// do nothing
|
||||
break;
|
||||
}
|
||||
|
||||
counter++;
|
||||
|
|
|
@ -268,7 +268,7 @@ int commander_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 40,
|
||||
3200,
|
||||
commander_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
|
||||
while (!thread_running) {
|
||||
usleep(200);
|
||||
|
|
|
@ -51,3 +51,6 @@ SRCS = commander.cpp \
|
|||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wframe-larger-than=2000
|
||||
|
||||
|
|
|
@ -42,4 +42,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \
|
|||
estimator_23states.cpp \
|
||||
estimator_utilities.cpp
|
||||
|
||||
EXTRACXXFLAGS = -Weffc++
|
||||
EXTRACXXFLAGS = -Weffc++ -Wframe-larger-than=6100
|
||||
|
||||
|
|
|
@ -115,7 +115,7 @@ int fixedwing_backside_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
control_demo_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -47,3 +47,5 @@ SRCS = fw_pos_control_l1_main.cpp \
|
|||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wno-float-equal
|
||||
|
|
|
@ -801,7 +801,7 @@ MavlinkFTP::_return_request(Request *req)
|
|||
|
||||
/// @brief Copy file (with limited space)
|
||||
int
|
||||
MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
|
||||
MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, size_t length)
|
||||
{
|
||||
char buff[512];
|
||||
int src_fd = -1, dst_fd = -1;
|
||||
|
|
|
@ -142,7 +142,7 @@ private:
|
|||
static void _worker_trampoline(void *arg);
|
||||
void _process_request(Request *req);
|
||||
void _reply(Request *req);
|
||||
int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
|
||||
int _copy_file(const char *src_path, const char *dst_path, size_t length);
|
||||
|
||||
ErrorCode _workList(PayloadHeader *payload);
|
||||
ErrorCode _workOpen(PayloadHeader *payload, int oflag);
|
||||
|
|
|
@ -948,7 +948,6 @@ Mavlink::configure_stream(const char *stream_name, const float rate)
|
|||
/* delete stream */
|
||||
LL_DELETE(_streams, stream);
|
||||
delete stream;
|
||||
warnx("deleted stream %s", stream->get_name());
|
||||
}
|
||||
|
||||
return OK;
|
||||
|
@ -1412,9 +1411,13 @@ Mavlink::task_main(int argc, char *argv[])
|
|||
configure_stream("SYS_STATUS", 1.0f);
|
||||
configure_stream("ATTITUDE", 50.0f);
|
||||
configure_stream("GLOBAL_POSITION_INT", 50.0f);
|
||||
configure_stream("LOCAL_POSITION_NED", 30.0f);
|
||||
configure_stream("CAMERA_CAPTURE", 2.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 10.0f);
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 10.0f);
|
||||
configure_stream("POSITION_TARGET_LOCAL_NED", 10.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 10.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 10.0f);
|
||||
configure_stream("VFR_HUD", 10.0f);
|
||||
break;
|
||||
|
||||
|
@ -1638,7 +1641,7 @@ Mavlink::start(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT,
|
||||
2800,
|
||||
(main_t)&Mavlink::start_helper,
|
||||
(const char **)argv);
|
||||
(char * const *)argv);
|
||||
|
||||
// Ensure that this shell command
|
||||
// does not return before the instance
|
||||
|
|
|
@ -1486,6 +1486,7 @@ protected:
|
|||
if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) {
|
||||
mavlink_position_target_global_int_t msg{};
|
||||
|
||||
msg.time_boot_ms = hrt_absolute_time()/1000;
|
||||
msg.coordinate_frame = MAV_FRAME_GLOBAL;
|
||||
msg.lat_int = pos_sp_triplet.current.lat * 1e7;
|
||||
msg.lon_int = pos_sp_triplet.current.lon * 1e7;
|
||||
|
@ -1764,6 +1765,9 @@ protected:
|
|||
case RC_INPUT_SOURCE_PX4IO_ST24:
|
||||
msg.rssi |= (3 << 4);
|
||||
break;
|
||||
case RC_INPUT_SOURCE_UNKNOWN:
|
||||
// do nothing
|
||||
break;
|
||||
}
|
||||
|
||||
if (rc.rc_lost) {
|
||||
|
|
|
@ -53,4 +53,6 @@ MAXOPTIMIZATION = -Os
|
|||
|
||||
MODULE_STACKSIZE = 1024
|
||||
|
||||
EXTRACXXFLAGS = -Weffc++
|
||||
EXTRACXXFLAGS = -Weffc++ -Wno-attributes -Wno-packed
|
||||
|
||||
EXTRACFLAGS = -Wno-packed
|
||||
|
|
|
@ -62,3 +62,5 @@ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
|
|||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wno-sign-compare
|
||||
|
|
|
@ -41,3 +41,6 @@ SRCS = position_estimator_inav_main.c \
|
|||
inertial_filter.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
EXTRACFLAGS = -Wframe-larger-than=3500
|
||||
|
||||
|
|
|
@ -152,7 +152,7 @@ int position_estimator_inav_main(int argc, char *argv[])
|
|||
position_estimator_inav_task = task_spawn_cmd("position_estimator_inav",
|
||||
SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 5000,
|
||||
position_estimator_inav_thread_main,
|
||||
(argv) ? (const char **) &argv[2] : (const char **) NULL);
|
||||
(argv) ? (char * const *) &argv[2] : (char * const *) NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -234,8 +234,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
|
||||
float eph_flow = 1.0f;
|
||||
|
||||
float eph_vision = 0.5f;
|
||||
float epv_vision = 0.5f;
|
||||
float eph_vision = 0.2f;
|
||||
float epv_vision = 0.2f;
|
||||
|
||||
float x_est_prev[2], y_est_prev[2], z_est_prev[2];
|
||||
memset(x_est_prev, 0, sizeof(x_est_prev));
|
||||
|
@ -641,6 +641,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
if (updated) {
|
||||
orb_copy(ORB_ID(vision_position_estimate), vision_position_estimate_sub, &vision);
|
||||
|
||||
static float last_vision_x = 0.0f;
|
||||
static float last_vision_y = 0.0f;
|
||||
static float last_vision_z = 0.0f;
|
||||
|
||||
/* reset position estimate on first vision update */
|
||||
if (!vision_valid) {
|
||||
x_est[0] = vision.x;
|
||||
|
@ -655,6 +659,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
}
|
||||
|
||||
vision_valid = true;
|
||||
|
||||
last_vision_x = vision.x;
|
||||
last_vision_y = vision.y;
|
||||
last_vision_z = vision.z;
|
||||
|
||||
warnx("VISION estimate valid");
|
||||
mavlink_log_info(mavlink_fd, "[inav] VISION estimate valid");
|
||||
}
|
||||
|
@ -664,10 +673,30 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
|||
corr_vision[1][0] = vision.y - y_est[0];
|
||||
corr_vision[2][0] = vision.z - z_est[0];
|
||||
|
||||
/* calculate correction for velocity */
|
||||
corr_vision[0][1] = vision.vx - x_est[1];
|
||||
corr_vision[1][1] = vision.vy - y_est[1];
|
||||
corr_vision[2][1] = vision.vz - z_est[1];
|
||||
static hrt_abstime last_vision_time = 0;
|
||||
|
||||
float vision_dt = (vision.timestamp_boot - last_vision_time) / 1e6f;
|
||||
last_vision_time = vision.timestamp_boot;
|
||||
|
||||
if (vision_dt > 0.000001f && vision_dt < 0.2f) {
|
||||
vision.vx = (vision.x - last_vision_x) / vision_dt;
|
||||
vision.vy = (vision.y - last_vision_y) / vision_dt;
|
||||
vision.vz = (vision.z - last_vision_z) / vision_dt;
|
||||
|
||||
last_vision_x = vision.x;
|
||||
last_vision_y = vision.y;
|
||||
last_vision_z = vision.z;
|
||||
|
||||
/* calculate correction for velocity */
|
||||
corr_vision[0][1] = vision.vx - x_est[1];
|
||||
corr_vision[1][1] = vision.vy - y_est[1];
|
||||
corr_vision[2][1] = vision.vz - z_est[1];
|
||||
} else {
|
||||
/* assume zero motion */
|
||||
corr_vision[0][1] = 0.0f - x_est[1];
|
||||
corr_vision[1][1] = 0.0f - y_est[1];
|
||||
corr_vision[2][1] = 0.0f - z_est[1];
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
|
|
@ -116,7 +116,7 @@ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f);
|
|||
* @max 10.0
|
||||
* @group Position Estimator INAV
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 5.0f);
|
||||
PARAM_DEFINE_FLOAT(INAV_W_XY_VIS_P, 7.0f);
|
||||
|
||||
/**
|
||||
* XY axis weight for vision velocity
|
||||
|
|
|
@ -45,3 +45,6 @@ SRCS = sdlog2.c \
|
|||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACFLAGS = -Wframe-larger-than=1200
|
||||
|
||||
|
|
|
@ -304,7 +304,7 @@ int sdlog2_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_DEFAULT - 30,
|
||||
3000,
|
||||
sdlog2_thread_main,
|
||||
(const char **)argv);
|
||||
(char * const *)argv);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
@ -1089,6 +1089,8 @@ int sdlog2_thread_main(int argc, char *argv[])
|
|||
|
||||
if (_extended_logging) {
|
||||
subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info));
|
||||
} else {
|
||||
subs.sat_info_sub = 0;
|
||||
}
|
||||
|
||||
/* close non-needed fd's */
|
||||
|
|
|
@ -468,7 +468,7 @@ static const struct log_format_s log_formats[] = {
|
|||
LOG_FORMAT(OUT0, "ffffffff", "Out0,Out1,Out2,Out3,Out4,Out5,Out6,Out7"),
|
||||
LOG_FORMAT(AIRS, "fff", "IndSpeed,TrueSpeed,AirTemp"),
|
||||
LOG_FORMAT(ARSP, "fff", "RollRateSP,PitchRateSP,YawRateSP"),
|
||||
LOG_FORMAT(FLOW, "hhfffBB", "RawX,RawY,CompX,CompY,Dist,Q,SensID"),
|
||||
LOG_FORMAT(FLOW, "QBffffffLLHhB", "IntT,ID,RawX,RawY,RX,RY,RZ,Dist,TSpan,DtSonar,FrmCnt,GT,Qlty"),
|
||||
LOG_FORMAT(GPOS, "LLfffffff", "Lat,Lon,Alt,VelN,VelE,VelD,EPH,EPV,TALT"),
|
||||
LOG_FORMAT(GPSP, "BLLffBfbf", "NavState,Lat,Lon,Alt,Yaw,Type,LoitR,LoitDir,PitMin"),
|
||||
LOG_FORMAT(ESC, "HBBBHHffiffH", "count,nESC,Conn,N,Ver,Adr,Volt,Amp,RPM,Temp,SetP,SetPRAW"),
|
||||
|
|
|
@ -110,7 +110,7 @@ int segway_main(int argc, char *argv[])
|
|||
SCHED_PRIORITY_MAX - 10,
|
||||
5120,
|
||||
segway_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
(argv) ? (char * const *)&argv[2] : (char * const *)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -44,3 +44,5 @@ SRCS = sensors.cpp \
|
|||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wno-type-limits
|
||||
|
|
|
@ -58,3 +58,5 @@ SRCS = err.c \
|
|||
mcu_version.c
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACFLAGS = -Wno-sign-compare
|
||||
|
|
|
@ -82,3 +82,17 @@ PARAM_DEFINE_INT32(SYS_USE_IO, 1);
|
|||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2);
|
||||
|
||||
/**
|
||||
* Companion computer interface
|
||||
*
|
||||
* Configures the baud rate of the companion computer interface.
|
||||
* Set to zero to disable, set to 921600 to enable.
|
||||
* CURRENTLY ONLY SUPPORTS 921600 BAUD! Use extras.txt for
|
||||
* other baud rates.
|
||||
*
|
||||
* @min 0
|
||||
* @max 921600
|
||||
* @group System
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SYS_COMPANION, 0);
|
||||
|
|
|
@ -87,7 +87,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
|
|||
kill(tcb->pid, SIGUSR1);
|
||||
}
|
||||
|
||||
int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, const char *argv[])
|
||||
int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
|
||||
{
|
||||
int pid;
|
||||
|
||||
|
|
|
@ -64,7 +64,7 @@ __EXPORT int task_spawn_cmd(const char *name,
|
|||
int scheduler,
|
||||
int stack_size,
|
||||
main_t entry,
|
||||
const char *argv[]);
|
||||
char * const argv[]);
|
||||
|
||||
enum MULT_PORTS {
|
||||
MULT_0_US2_RXTX = 0,
|
||||
|
|
|
@ -67,6 +67,33 @@ typedef const struct orb_metadata *orb_id_t;
|
|||
*/
|
||||
#define ORB_ID(_name) &__orb_##_name
|
||||
|
||||
/**
|
||||
* Generates a pointer to the uORB metadata structure for
|
||||
* a given topic.
|
||||
*
|
||||
* The topic must have been declared previously in scope
|
||||
* with ORB_DECLARE().
|
||||
*
|
||||
* @param _name The name of the topic.
|
||||
* @param _count The class ID of the topic
|
||||
*/
|
||||
#define ORB_ID_DOUBLE(_name, _count) ((_count == CLASS_DEVICE_PRIMARY) ? &__orb_##_name##0 : &__orb_##_name##1)
|
||||
|
||||
/**
|
||||
* Generates a pointer to the uORB metadata structure for
|
||||
* a given topic.
|
||||
*
|
||||
* The topic must have been declared previously in scope
|
||||
* with ORB_DECLARE().
|
||||
*
|
||||
* @param _name The name of the topic.
|
||||
* @param _count The class ID of the topic
|
||||
*/
|
||||
#define ORB_ID_TRIPLE(_name, _count) \
|
||||
((_count == CLASS_DEVICE_PRIMARY) ? &__orb_##_name##0 : \
|
||||
((_count == CLASS_DEVICE_SECONDARY) ? &__orb_##_name##1 : \
|
||||
(((_count == CLASS_DEVICE_TERTIARY) ? &__orb_##_name##2 : 0))))
|
||||
|
||||
/**
|
||||
* Declare (prototype) the uORB metadata for a topic.
|
||||
*
|
||||
|
|
|
@ -39,3 +39,6 @@ MODULE_COMMAND = vtol_att_control
|
|||
|
||||
SRCS = vtol_att_control_main.cpp \
|
||||
vtol_att_control_params.c
|
||||
|
||||
EXTRACXXFLAGS = -Wno-write-strings
|
||||
|
||||
|
|
|
@ -52,6 +52,8 @@
|
|||
#include "systemlib/systemlib.h"
|
||||
#include "systemlib/err.h"
|
||||
|
||||
#define BL_FILE_SIZE_LIMIT 16384
|
||||
|
||||
__EXPORT int bl_update_main(int argc, char *argv[]);
|
||||
|
||||
static void setopt(void);
|
||||
|
@ -72,12 +74,12 @@ bl_update_main(int argc, char *argv[])
|
|||
|
||||
struct stat s;
|
||||
|
||||
if (stat(argv[1], &s) < 0)
|
||||
if (!stat(argv[1], &s))
|
||||
err(1, "stat %s", argv[1]);
|
||||
|
||||
/* sanity-check file size */
|
||||
if (s.st_size > 16384)
|
||||
errx(1, "%s: file too large", argv[1]);
|
||||
if (s.st_size > BL_FILE_SIZE_LIMIT)
|
||||
errx(1, "%s: file too large (limit: %u, actual: %d)", argv[1], BL_FILE_SIZE_LIMIT, s.st_size);
|
||||
|
||||
uint8_t *buf = malloc(s.st_size);
|
||||
|
||||
|
|
|
@ -41,3 +41,6 @@ SRCS = mixer.cpp
|
|||
MODULE_STACKSIZE = 4096
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACXXFLAGS = -Wframe-larger-than=2048
|
||||
|
||||
|
|
|
@ -6,3 +6,6 @@ MODULE_COMMAND = mtd
|
|||
SRCS = mtd.c 24xxxx_mtd.c
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
EXTRACFLAGS = -Wno-error
|
||||
|
||||
|
|
|
@ -212,7 +212,7 @@ static void
|
|||
do_show(const char* search_string)
|
||||
{
|
||||
printf(" + = saved, * = unsaved\n");
|
||||
param_foreach(do_show_print, search_string, false);
|
||||
param_foreach(do_show_print, (char *)search_string, false);
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
|
|
@ -34,3 +34,6 @@ SRCS = test_adc.c \
|
|||
test_conv.cpp \
|
||||
test_mount.c \
|
||||
test_mtd.c
|
||||
|
||||
EXTRACXXFLAGS = -Wframe-larger-than=2500
|
||||
|
||||
|
|
|
@ -1,6 +1,8 @@
|
|||
./obj/*
|
||||
gtest_main.a
|
||||
mixer_test
|
||||
sf0x_test
|
||||
sbus2_test
|
||||
autodeclination_test
|
||||
st24_test
|
||||
sample_unittest
|
||||
|
|
|
@ -3,7 +3,44 @@ CC=g++
|
|||
CFLAGS=-I. -I../src/modules -I ../src/include -I../src/drivers \
|
||||
-I../src -I../src/lib -D__EXPORT="" -Dnullptr="0" -lm
|
||||
|
||||
all: mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
# Points to the root of Google Test, relative to where this file is.
|
||||
# Remember to tweak this if you move this file.
|
||||
GTEST_DIR = gtest
|
||||
|
||||
# Flags passed to the preprocessor.
|
||||
# Set Google Test's header directory as a system directory, such that
|
||||
# the compiler doesn't generate warnings in Google Test headers.
|
||||
CFLAGS += -isystem $(GTEST_DIR)/include
|
||||
|
||||
# All Google Test headers. Usually you shouldn't change this
|
||||
# definition.
|
||||
GTEST_HEADERS = $(GTEST_DIR)/include/gtest/*.h \
|
||||
$(GTEST_DIR)/include/gtest/internal/*.h
|
||||
|
||||
# Usually you shouldn't tweak such internal variables, indicated by a
|
||||
# trailing _.
|
||||
GTEST_SRCS_ = $(GTEST_DIR)/src/*.cc $(GTEST_DIR)/src/*.h $(GTEST_HEADERS)
|
||||
|
||||
# For simplicity and to avoid depending on Google Test's
|
||||
# implementation details, the dependencies specified below are
|
||||
# conservative and not optimized. This is fine as Google Test
|
||||
# compiles fast and for ordinary users its source rarely changes.
|
||||
gtest-all.o: $(GTEST_SRCS_)
|
||||
$(CC) $(CFLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest-all.cc
|
||||
|
||||
gtest_main.o: $(GTEST_SRCS_)
|
||||
$(CC) $(CFLAGS) -I$(GTEST_DIR) -c \
|
||||
$(GTEST_DIR)/src/gtest_main.cc
|
||||
|
||||
gtest.a: gtest-all.o
|
||||
$(AR) $(ARFLAGS) $@ $^
|
||||
|
||||
gtest_main.a: gtest-all.o gtest_main.o
|
||||
$(AR) $(ARFLAGS) $@ $^
|
||||
|
||||
|
||||
all: sample_unittest mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
|
||||
MIXER_FILES=../src/systemcmds/tests/test_mixer.cpp \
|
||||
../src/systemcmds/tests/test_conv.cpp \
|
||||
|
@ -33,6 +70,20 @@ AUTODECLINATION_FILES= ../src/lib/geo_lookup/geo_mag_declination.c \
|
|||
hrt.cpp \
|
||||
autodeclination_test.cpp
|
||||
|
||||
# Builds a sample test. A test should link with either gtest.a or
|
||||
# gtest_main.a, depending on whether it defines its own main()
|
||||
# function.
|
||||
sample.o: sample.cc sample.h $(GTEST_HEADERS)
|
||||
$(CC) $(CFLAGS) -c sample.cc
|
||||
|
||||
sample_unittest.o: sample_unittest.cc \
|
||||
sample.h $(GTEST_HEADERS)
|
||||
$(CC) $(CFLAGS) -c sample_unittest.cc
|
||||
|
||||
sample_unittest: sample.o sample_unittest.o gtest_main.a
|
||||
$(CC) $(CFLAGS) $^ -o $@
|
||||
|
||||
|
||||
mixer_test: $(MIXER_FILES)
|
||||
$(CC) -o mixer_test $(MIXER_FILES) $(CFLAGS)
|
||||
|
||||
|
@ -57,4 +108,4 @@ unittests: clean mixer_test sbus2_test sf0x_test autodeclination_test st24_test
|
|||
|
||||
.PHONY: clean
|
||||
clean:
|
||||
rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
rm -f gtest.a gtest_main.a *.o $(ODIR)/*.o *~ core $(INCDIR)/*~ sample_unittest mixer_test sbus2_test autodeclination_test st24_test sf0x_test
|
||||
|
|
|
@ -0,0 +1 @@
|
|||
Subproject commit cdef6e4ce097f953445446e8da4cb8bb68478bc5
|
|
@ -0,0 +1,68 @@
|
|||
// Copyright 2005, Google Inc.
|
||||
// All rights reserved.
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are
|
||||
// met:
|
||||
//
|
||||
// * Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
// * 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.
|
||||
// * Neither the name of Google Inc. 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.
|
||||
|
||||
// A sample program demonstrating using Google C++ testing framework.
|
||||
//
|
||||
// Author: wan@google.com (Zhanyong Wan)
|
||||
|
||||
#include "sample.h"
|
||||
|
||||
// Returns n! (the factorial of n). For negative n, n! is defined to be 1.
|
||||
int Factorial(int n) {
|
||||
int result = 1;
|
||||
for (int i = 1; i <= n; i++) {
|
||||
result *= i;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
// Returns true iff n is a prime number.
|
||||
bool IsPrime(int n) {
|
||||
// Trivial case 1: small numbers
|
||||
if (n <= 1) return false;
|
||||
|
||||
// Trivial case 2: even numbers
|
||||
if (n % 2 == 0) return n == 2;
|
||||
|
||||
// Now, we have that n is odd and n >= 3.
|
||||
|
||||
// Try to divide n by every odd number i, starting from 3
|
||||
for (int i = 3; ; i += 2) {
|
||||
// We only have to try i up to the squre root of n
|
||||
if (i > n/i) break;
|
||||
|
||||
// Now, we have i <= n/i < n.
|
||||
// If n is divisible by i, n is not prime.
|
||||
if (n % i == 0) return false;
|
||||
}
|
||||
|
||||
// n has no integer factor in the range (1, n), and thus is prime.
|
||||
return true;
|
||||
}
|
|
@ -0,0 +1,43 @@
|
|||
// Copyright 2005, Google Inc.
|
||||
// All rights reserved.
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are
|
||||
// met:
|
||||
//
|
||||
// * Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
// * 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.
|
||||
// * Neither the name of Google Inc. 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.
|
||||
|
||||
// A sample program demonstrating using Google C++ testing framework.
|
||||
//
|
||||
// Author: wan@google.com (Zhanyong Wan)
|
||||
|
||||
#ifndef GTEST_SAMPLES_SAMPLE1_H_
|
||||
#define GTEST_SAMPLES_SAMPLE1_H_
|
||||
|
||||
// Returns n! (the factorial of n). For negative n, n! is defined to be 1.
|
||||
int Factorial(int n);
|
||||
|
||||
// Returns true iff n is a prime number.
|
||||
bool IsPrime(int n);
|
||||
|
||||
#endif // GTEST_SAMPLES_SAMPLE1_H_
|
|
@ -0,0 +1,153 @@
|
|||
// Copyright 2005, Google Inc.
|
||||
// All rights reserved.
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are
|
||||
// met:
|
||||
//
|
||||
// * Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
// * 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.
|
||||
// * Neither the name of Google Inc. 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.
|
||||
|
||||
// A sample program demonstrating using Google C++ testing framework.
|
||||
//
|
||||
// Author: wan@google.com (Zhanyong Wan)
|
||||
|
||||
|
||||
// This sample shows how to write a simple unit test for a function,
|
||||
// using Google C++ testing framework.
|
||||
//
|
||||
// Writing a unit test using Google C++ testing framework is easy as 1-2-3:
|
||||
|
||||
|
||||
// Step 1. Include necessary header files such that the stuff your
|
||||
// test logic needs is declared.
|
||||
//
|
||||
// Don't forget gtest.h, which declares the testing framework.
|
||||
|
||||
#include <limits.h>
|
||||
#include "sample.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
|
||||
// Step 2. Use the TEST macro to define your tests.
|
||||
//
|
||||
// TEST has two parameters: the test case name and the test name.
|
||||
// After using the macro, you should define your test logic between a
|
||||
// pair of braces. You can use a bunch of macros to indicate the
|
||||
// success or failure of a test. EXPECT_TRUE and EXPECT_EQ are
|
||||
// examples of such macros. For a complete list, see gtest.h.
|
||||
//
|
||||
// <TechnicalDetails>
|
||||
//
|
||||
// In Google Test, tests are grouped into test cases. This is how we
|
||||
// keep test code organized. You should put logically related tests
|
||||
// into the same test case.
|
||||
//
|
||||
// The test case name and the test name should both be valid C++
|
||||
// identifiers. And you should not use underscore (_) in the names.
|
||||
//
|
||||
// Google Test guarantees that each test you define is run exactly
|
||||
// once, but it makes no guarantee on the order the tests are
|
||||
// executed. Therefore, you should write your tests in such a way
|
||||
// that their results don't depend on their order.
|
||||
//
|
||||
// </TechnicalDetails>
|
||||
|
||||
|
||||
// Tests Factorial().
|
||||
|
||||
// Tests factorial of negative numbers.
|
||||
TEST(FactorialTest, Negative) {
|
||||
// This test is named "Negative", and belongs to the "FactorialTest"
|
||||
// test case.
|
||||
EXPECT_EQ(1, Factorial(-5));
|
||||
EXPECT_EQ(1, Factorial(-1));
|
||||
EXPECT_GT(Factorial(-10), 0);
|
||||
|
||||
// <TechnicalDetails>
|
||||
//
|
||||
// EXPECT_EQ(expected, actual) is the same as
|
||||
//
|
||||
// EXPECT_TRUE((expected) == (actual))
|
||||
//
|
||||
// except that it will print both the expected value and the actual
|
||||
// value when the assertion fails. This is very helpful for
|
||||
// debugging. Therefore in this case EXPECT_EQ is preferred.
|
||||
//
|
||||
// On the other hand, EXPECT_TRUE accepts any Boolean expression,
|
||||
// and is thus more general.
|
||||
//
|
||||
// </TechnicalDetails>
|
||||
}
|
||||
|
||||
// Tests factorial of 0.
|
||||
TEST(FactorialTest, Zero) {
|
||||
EXPECT_EQ(1, Factorial(0));
|
||||
}
|
||||
|
||||
// Tests factorial of positive numbers.
|
||||
TEST(FactorialTest, Positive) {
|
||||
EXPECT_EQ(1, Factorial(1));
|
||||
EXPECT_EQ(2, Factorial(2));
|
||||
EXPECT_EQ(6, Factorial(3));
|
||||
EXPECT_EQ(40320, Factorial(8));
|
||||
}
|
||||
|
||||
|
||||
// Tests IsPrime()
|
||||
|
||||
// Tests negative input.
|
||||
TEST(IsPrimeTest, Negative) {
|
||||
// This test belongs to the IsPrimeTest test case.
|
||||
|
||||
EXPECT_FALSE(IsPrime(-1));
|
||||
EXPECT_FALSE(IsPrime(-2));
|
||||
EXPECT_FALSE(IsPrime(INT_MIN));
|
||||
}
|
||||
|
||||
// Tests some trivial cases.
|
||||
TEST(IsPrimeTest, Trivial) {
|
||||
EXPECT_FALSE(IsPrime(0));
|
||||
EXPECT_FALSE(IsPrime(1));
|
||||
EXPECT_TRUE(IsPrime(2));
|
||||
EXPECT_TRUE(IsPrime(3));
|
||||
}
|
||||
|
||||
// Tests positive input.
|
||||
TEST(IsPrimeTest, Positive) {
|
||||
EXPECT_FALSE(IsPrime(4));
|
||||
EXPECT_TRUE(IsPrime(5));
|
||||
EXPECT_FALSE(IsPrime(6));
|
||||
EXPECT_TRUE(IsPrime(23));
|
||||
}
|
||||
|
||||
// Step 3. Call RUN_ALL_TESTS() in main().
|
||||
//
|
||||
// We do this by linking in src/gtest_main.cc file, which consists of
|
||||
// a main() function which calls RUN_ALL_TESTS() for us.
|
||||
//
|
||||
// This runs all the tests you've defined, prints the result, and
|
||||
// returns 0 if successful, or 1 otherwise.
|
||||
//
|
||||
// Did you notice that we didn't register the tests? The
|
||||
// RUN_ALL_TESTS() macro magically knows about all the tests we
|
||||
// defined. Isn't this convenient?
|
Loading…
Reference in New Issue