Merge remote-tracking branch 'upstream/master' into dev_ros

Conflicts:
	.gitmodules
This commit is contained in:
Thomas Gubler
2014-12-29 08:00:12 +01:00
82 changed files with 651 additions and 87 deletions
+3
View File
@@ -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
+7 -5
View File
@@ -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
+1 -1
Submodule NuttX updated: b66de65069...3c36467c0d
+1 -1
View File
@@ -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
+1
View File
@@ -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
+10
View File
@@ -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
+1
View File
@@ -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
+1
View File
@@ -127,6 +127,7 @@ ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics
#
ARCHWARNINGS = -Wall \
-Wextra \
-Werror \
-Wdouble-promotion \
-Wshadow \
-Wfloat-equal \
+1
View File
@@ -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 \
+1
View File
@@ -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 \
+1 -1
View File
@@ -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
+1
View File
@@ -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 \
+1 -1
View File
@@ -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
+1
View File
@@ -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 \
+1
View File
@@ -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);
}
+2 -1
View File
@@ -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
+15
View File
@@ -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);
+1 -1
View File
@@ -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);
}
+1 -3
View File
@@ -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);
}
+1 -3
View File
@@ -37,8 +37,6 @@
MODULE_COMMAND = hott_telemetry
SRCS = hott_telemetry.cpp \
../messages.cpp \
../comms.cpp
SRCS = hott_telemetry.cpp
MAXOPTIMIZATION = -Os
+9 -9
View File
@@ -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_ */
+41
View File
@@ -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
+2
View File
@@ -40,3 +40,5 @@ MODULE_COMMAND = px4flow
SRCS = px4flow.cpp
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wno-attributes
+1 -1
View File
@@ -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;
+1 -1
View File
@@ -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")) {
+3 -1
View File
@@ -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
{
+1 -1
View File
@@ -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;
+1 -1
View File
@@ -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);
}
+2
View File
@@ -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
+7 -5
View File
@@ -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);
}
+6 -3
View File
@@ -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);
}
+5
View File
@@ -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;
+1 -1
View File
@@ -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
+7
View File
@@ -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++;
+1 -1
View File
@@ -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);
+3
View File
@@ -51,3 +51,6 @@ SRCS = commander.cpp \
MODULE_STACKSIZE = 1200
MAXOPTIMIZATION = -Os
EXTRACXXFLAGS = -Wframe-larger-than=2000
+2 -1
View File
@@ -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);
}

Some files were not shown because too many files have changed in this diff Show More