mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-17 04:27:34 +08:00
Merge remote-tracking branch 'upstream/master' into romfs_clean
Conflicts: ROMFS/px4fmu_common/init.d/rc.interface ROMFS/px4fmu_common/init.d/rcS
This commit is contained in:
+1
-1
Submodule NuttX updated: 9d06b64579...c7b0638592
@@ -2,4 +2,4 @@
|
||||
|
||||
sh /etc/init.d/rc.fw_defaults
|
||||
|
||||
set MIXER FMU_AERT
|
||||
set MIXER skywalker
|
||||
@@ -0,0 +1,64 @@
|
||||
Mixer for Skywalker Airframe
|
||||
==================================================
|
||||
|
||||
This file defines mixers suitable for controlling a fixed wing aircraft with
|
||||
aileron, rudder, elevator and throttle controls using PX4FMU. The configuration
|
||||
assumes the aileron servo(s) are connected to PX4FMU servo output 0, the
|
||||
elevator to output 1, the rudder to output 2 and the throttle to output 3.
|
||||
|
||||
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
|
||||
(roll), 1 (pitch) and 3 (thrust).
|
||||
|
||||
Aileron mixer
|
||||
-------------
|
||||
Two scalers total (output, roll).
|
||||
|
||||
This mixer assumes that the aileron servos are set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
As there is only one output, if using two servos adjustments to compensate for
|
||||
differences between the servos must be made mechanically. To obtain the correct
|
||||
motion using a Y cable, the servos can be positioned reversed from one another.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 0 -10000 -10000 0 -10000 10000
|
||||
|
||||
Elevator mixer
|
||||
------------
|
||||
Two scalers total (output, roll).
|
||||
|
||||
This mixer assumes that the elevator servo is set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 1 10000 10000 0 -10000 10000
|
||||
|
||||
Rudder mixer
|
||||
------------
|
||||
Two scalers total (output, yaw).
|
||||
|
||||
This mixer assumes that the rudder servo is set up correctly mechanically;
|
||||
depending on the actual configuration it may be necessary to reverse the scaling
|
||||
factors (to reverse the servo movement) and adjust the offset, scaling and
|
||||
endpoints to suit.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 2 10000 10000 0 -10000 10000
|
||||
|
||||
Motor speed mixer
|
||||
-----------------
|
||||
Two scalers total (output, thrust).
|
||||
|
||||
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
|
||||
range. Inputs below zero are treated as zero.
|
||||
|
||||
M: 1
|
||||
O: 10000 10000 0 -10000 10000
|
||||
S: 0 3 0 20000 -10000 -10000 10000
|
||||
@@ -73,6 +73,7 @@ parser.add_argument("--version", action="store", help="set a version string")
|
||||
parser.add_argument("--summary", action="store", help="set a brief description")
|
||||
parser.add_argument("--description", action="store", help="set a longer description")
|
||||
parser.add_argument("--git_identity", action="store", help="the working directory to check for git identity")
|
||||
parser.add_argument("--parameter_xml", action="store", help="the parameters.xml file")
|
||||
parser.add_argument("--image", action="store", help="the firmware image")
|
||||
args = parser.parse_args()
|
||||
|
||||
@@ -101,6 +102,10 @@ if args.git_identity != None:
|
||||
p = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE).stdout
|
||||
desc['git_identity'] = str(p.read().strip())
|
||||
p.close()
|
||||
if args.parameter_xml != None:
|
||||
f = open(args.parameter_xml, "rb")
|
||||
bytes = f.read()
|
||||
desc['parameter_xml'] = base64.b64encode(zlib.compress(bytes,9)).decode('utf-8')
|
||||
if args.image != None:
|
||||
f = open(args.image, "rb")
|
||||
bytes = f.read()
|
||||
|
||||
@@ -24,6 +24,8 @@ MODULES += drivers/l3gd20
|
||||
MODULES += drivers/mpu6000
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
#MODULES += drivers/ll40ls
|
||||
MODULES += drivers/trone
|
||||
#MODULES += drivers/mb12xx
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
@@ -132,6 +134,9 @@ MODULES += lib/launchdetection
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
# Generate parameter XML file
|
||||
GEN_PARAM_XML = 1
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
|
||||
@@ -27,13 +27,14 @@ MODULES += drivers/l3gd20
|
||||
MODULES += drivers/hmc5883
|
||||
MODULES += drivers/ms5611
|
||||
MODULES += drivers/mb12xx
|
||||
MODULES += drivers/sf0x
|
||||
# MODULES += drivers/sf0x
|
||||
MODULES += drivers/ll40ls
|
||||
# MODULES += drivers/trone
|
||||
MODULES += drivers/gps
|
||||
MODULES += drivers/hil
|
||||
MODULES += drivers/hott/hott_telemetry
|
||||
MODULES += drivers/hott/hott_sensors
|
||||
MODULES += drivers/blinkm
|
||||
# MODULES += drivers/blinkm
|
||||
MODULES += drivers/airspeed
|
||||
MODULES += drivers/ets_airspeed
|
||||
MODULES += drivers/meas_airspeed
|
||||
@@ -141,6 +142,9 @@ MODULES += modules/bottle_drop
|
||||
# Hardware test
|
||||
#MODULES += examples/hwtest
|
||||
|
||||
# Generate parameter XML file
|
||||
GEN_PARAM_XML = 1
|
||||
|
||||
#
|
||||
# Transitional support - add commands from the NuttX export archive.
|
||||
#
|
||||
|
||||
@@ -50,16 +50,25 @@ MODULES += lib/mathlib/math/filter
|
||||
MODULES += lib/conversion
|
||||
|
||||
#
|
||||
# Modules to test-build, but not useful for test environment
|
||||
# Example modules to test-build
|
||||
#
|
||||
MODULES += examples/flow_position_estimator
|
||||
MODULES += examples/fixedwing_control
|
||||
MODULES += examples/hwtest
|
||||
MODULES += examples/matlab_csv_serial
|
||||
MODULES += examples/px4_daemon_app
|
||||
MODULES += examples/px4_mavlink_debug
|
||||
MODULES += examples/px4_simple_app
|
||||
|
||||
#
|
||||
# Drivers / modules to test build, but not useful for test environment
|
||||
#
|
||||
MODULES += modules/attitude_estimator_so3
|
||||
MODULES += drivers/pca8574
|
||||
MODULES += examples/flow_position_estimator
|
||||
|
||||
#
|
||||
# Libraries
|
||||
# Tests
|
||||
#
|
||||
LIBRARIES += lib/mathlib/CMSIS
|
||||
|
||||
MODULES += modules/unit_test
|
||||
MODULES += modules/mavlink/mavlink_tests
|
||||
|
||||
@@ -467,6 +467,7 @@ endif
|
||||
PRODUCT_BUNDLE = $(WORK_DIR)firmware.px4
|
||||
PRODUCT_BIN = $(WORK_DIR)firmware.bin
|
||||
PRODUCT_ELF = $(WORK_DIR)firmware.elf
|
||||
PRODUCT_PARAMXML = $(WORK_DIR)/parameters.xml
|
||||
|
||||
.PHONY: firmware
|
||||
firmware: $(PRODUCT_BUNDLE)
|
||||
@@ -497,9 +498,17 @@ $(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
|
||||
|
||||
$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
|
||||
@$(ECHO) %% Generating $@
|
||||
ifdef GEN_PARAM_XML
|
||||
python $(PX4_BASE)/Tools/px_process_params.py --src-path $(PX4_BASE)/src --xml
|
||||
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
|
||||
--git_identity $(PX4_BASE) \
|
||||
--parameter_xml $(PRODUCT_PARAMXML) \
|
||||
--image $< > $@
|
||||
else
|
||||
$(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
|
||||
--git_identity $(PX4_BASE) \
|
||||
--image $< > $@
|
||||
endif
|
||||
|
||||
$(PRODUCT_BIN): $(PRODUCT_ELF)
|
||||
$(call SYM_TO_BIN,$<,$@)
|
||||
|
||||
@@ -50,11 +50,11 @@ OBJDUMP = $(CROSSDEV)objdump
|
||||
|
||||
# Check if the right version of the toolchain is available
|
||||
#
|
||||
CROSSDEV_VER_SUPPORTED = 4.7
|
||||
CROSSDEV_VER_SUPPORTED = 4.7.4 4.7.5 4.7.6 4.8.4
|
||||
CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion)
|
||||
|
||||
ifeq (,$(findstring $(CROSSDEV_VER_SUPPORTED),$(CROSSDEV_VER_FOUND)))
|
||||
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of $(CROSSDEV_VER_SUPPORTED).x)
|
||||
ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
|
||||
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of one in: $(CROSSDEV_VER_SUPPORTED))
|
||||
endif
|
||||
|
||||
|
||||
|
||||
@@ -159,13 +159,15 @@ out:
|
||||
int
|
||||
Airspeed::probe()
|
||||
{
|
||||
/* on initial power up the device needs more than one retry
|
||||
for detection. Once it is running then retries aren't
|
||||
needed
|
||||
/* on initial power up the device may need more than one retry
|
||||
for detection. Once it is running the number of retries can
|
||||
be reduced
|
||||
*/
|
||||
_retries = 4;
|
||||
int ret = measure();
|
||||
_retries = 0;
|
||||
|
||||
// drop back to 2 retries once initialised
|
||||
_retries = 2;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
@@ -274,7 +274,6 @@ GPS::task_main_trampoline(void *arg)
|
||||
void
|
||||
GPS::task_main()
|
||||
{
|
||||
log("starting");
|
||||
|
||||
/* open the serial port */
|
||||
_serial_fd = ::open(_port, O_RDWR);
|
||||
|
||||
@@ -1349,7 +1349,7 @@ HMC5883 *g_dev_ext = nullptr;
|
||||
void start(int bus, enum Rotation rotation);
|
||||
void test(int bus);
|
||||
void reset(int bus);
|
||||
void info(int bus);
|
||||
int info(int bus);
|
||||
int calibrate(int bus);
|
||||
void usage();
|
||||
|
||||
@@ -1595,17 +1595,23 @@ reset(int bus)
|
||||
/**
|
||||
* Print a little info about the driver.
|
||||
*/
|
||||
void
|
||||
int
|
||||
info(int bus)
|
||||
{
|
||||
HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext);
|
||||
if (g_dev == nullptr)
|
||||
errx(1, "driver not running");
|
||||
int ret = 1;
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
g_dev->print_info();
|
||||
HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD ? g_dev_int : g_dev_ext);
|
||||
if (g_dev == nullptr) {
|
||||
warnx("not running on bus %d", bus);
|
||||
} else {
|
||||
|
||||
exit(0);
|
||||
warnx("running on bus: %d (%s)\n", bus, ((PX4_I2C_BUS_ONBOARD) ? "onboard" : "offboard"));
|
||||
|
||||
g_dev->print_info();
|
||||
ret = 0;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
@@ -1685,8 +1691,21 @@ hmc5883_main(int argc, char *argv[])
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(verb, "info") || !strcmp(verb, "status"))
|
||||
hmc5883::info(bus);
|
||||
if (!strcmp(verb, "info") || !strcmp(verb, "status")) {
|
||||
if (bus == -1) {
|
||||
int ret = 0;
|
||||
if (hmc5883::info(PX4_I2C_BUS_ONBOARD)) {
|
||||
ret = 1;
|
||||
}
|
||||
|
||||
if (hmc5883::info(PX4_I2C_BUS_EXPANSION)) {
|
||||
ret = 1;
|
||||
}
|
||||
exit(ret);
|
||||
} else {
|
||||
exit(hmc5883::info(bus));
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
* Autocalibrate the scaling
|
||||
|
||||
+200
-143
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2013, 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
|
||||
@@ -73,15 +73,13 @@
|
||||
#include <board_config.h>
|
||||
|
||||
/* Configuration Constants */
|
||||
#define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION
|
||||
#define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84
|
||||
//range 0x42 - 0x49
|
||||
|
||||
/* PX4FLOW Registers addresses */
|
||||
#define PX4FLOW_REG 0x00 /* Measure Register */
|
||||
|
||||
#define PX4FLOW_CONVERSION_INTERVAL 8000 /* 8ms 125Hz */
|
||||
#define PX4FLOW_REG 0x16 /* Measure Register 22*/
|
||||
|
||||
#define PX4FLOW_CONVERSION_INTERVAL 20000 //in microseconds! 20000 = 50 Hz 100000 = 10Hz
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
@@ -92,28 +90,42 @@ static const int ERROR = -1;
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
//struct i2c_frame
|
||||
//{
|
||||
// uint16_t frame_count;
|
||||
// int16_t pixel_flow_x_sum;
|
||||
// int16_t pixel_flow_y_sum;
|
||||
// int16_t flow_comp_m_x;
|
||||
// int16_t flow_comp_m_y;
|
||||
// int16_t qual;
|
||||
// int16_t gyro_x_rate;
|
||||
// int16_t gyro_y_rate;
|
||||
// int16_t gyro_z_rate;
|
||||
// uint8_t gyro_range;
|
||||
// uint8_t sonar_timestamp;
|
||||
// int16_t ground_distance;
|
||||
//};
|
||||
//
|
||||
//struct i2c_frame f;
|
||||
struct i2c_frame {
|
||||
uint16_t frame_count;
|
||||
int16_t pixel_flow_x_sum;
|
||||
int16_t pixel_flow_y_sum;
|
||||
int16_t flow_comp_m_x;
|
||||
int16_t flow_comp_m_y;
|
||||
int16_t qual;
|
||||
int16_t gyro_x_rate;
|
||||
int16_t gyro_y_rate;
|
||||
int16_t gyro_z_rate;
|
||||
uint8_t gyro_range;
|
||||
uint8_t sonar_timestamp;
|
||||
int16_t ground_distance;
|
||||
};
|
||||
struct i2c_frame f;
|
||||
|
||||
class PX4FLOW : public device::I2C
|
||||
typedef struct i2c_integral_frame {
|
||||
uint16_t frame_count_since_last_readout;
|
||||
int16_t pixel_flow_x_integral;
|
||||
int16_t pixel_flow_y_integral;
|
||||
int16_t gyro_x_rate_integral;
|
||||
int16_t gyro_y_rate_integral;
|
||||
int16_t gyro_z_rate_integral;
|
||||
uint32_t integration_timespan;
|
||||
uint32_t time_since_last_sonar_update;
|
||||
uint16_t ground_distance;
|
||||
int16_t gyro_temperature;
|
||||
uint8_t qual;
|
||||
} __attribute__((packed));
|
||||
struct i2c_integral_frame f_integral;
|
||||
|
||||
|
||||
class PX4FLOW: public device::I2C
|
||||
{
|
||||
public:
|
||||
PX4FLOW(int bus = PX4FLOW_BUS, int address = I2C_FLOW_ADDRESS);
|
||||
PX4FLOW(int bus, int address = I2C_FLOW_ADDRESS);
|
||||
virtual ~PX4FLOW();
|
||||
|
||||
virtual int init();
|
||||
@@ -122,8 +134,8 @@ public:
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
protected:
|
||||
@@ -144,42 +156,41 @@ private:
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/**
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
*
|
||||
* @param address The I2C bus address to probe.
|
||||
* @return True if the device is present.
|
||||
*/
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
*
|
||||
* @param address The I2C bus address to probe.
|
||||
* @return True if the device is present.
|
||||
*/
|
||||
int probe_address(uint8_t address);
|
||||
|
||||
/**
|
||||
* Initialise the automatic measurement state machine and start it.
|
||||
*
|
||||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
* Initialise the automatic measurement state machine and start it.
|
||||
*
|
||||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
void start();
|
||||
|
||||
/**
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
*/
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
*/
|
||||
void cycle();
|
||||
int measure();
|
||||
int collect();
|
||||
/**
|
||||
* Static trampoline from the workq context; because we don't have a
|
||||
* generic workq wrapper yet.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
* Static trampoline from the workq context; because we don't have a
|
||||
* generic workq wrapper yet.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
};
|
||||
|
||||
@@ -189,7 +200,7 @@ private:
|
||||
extern "C" __EXPORT int px4flow_main(int argc, char *argv[]);
|
||||
|
||||
PX4FLOW::PX4FLOW(int bus, int address) :
|
||||
I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000),//400khz
|
||||
I2C("PX4FLOW", PX4FLOW_DEVICE_PATH, bus, address, 400000), //400khz
|
||||
_reports(nullptr),
|
||||
_sensor_ok(false),
|
||||
_measure_ticks(0),
|
||||
@@ -228,21 +239,12 @@ PX4FLOW::init()
|
||||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(struct optical_flow_s));
|
||||
_reports = new RingBuffer(2, sizeof(optical_flow_s));
|
||||
|
||||
if (_reports == nullptr) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* get a publish handle on the px4flow topic */
|
||||
struct optical_flow_s zero_report;
|
||||
memset(&zero_report, 0, sizeof(zero_report));
|
||||
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report);
|
||||
|
||||
if (_px4flow_topic < 0) {
|
||||
warnx("failed to create px4flow object. Did you start uOrb?");
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
/* sensor is ok, but we don't really know if it is within range */
|
||||
_sensor_ok = true;
|
||||
@@ -410,9 +412,6 @@ PX4FLOW::read(struct file *filp, char *buffer, size_t buflen)
|
||||
break;
|
||||
}
|
||||
|
||||
/* wait for it to complete */
|
||||
usleep(PX4FLOW_CONVERSION_INTERVAL);
|
||||
|
||||
/* run the collection phase */
|
||||
if (OK != collect()) {
|
||||
ret = -EIO;
|
||||
@@ -442,6 +441,7 @@ PX4FLOW::measure()
|
||||
|
||||
if (OK != ret) {
|
||||
perf_count(_comms_errors);
|
||||
debug("i2c::transfer returned %d", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -453,14 +453,20 @@ PX4FLOW::measure()
|
||||
int
|
||||
PX4FLOW::collect()
|
||||
{
|
||||
int ret = -EIO;
|
||||
int ret = -EIO;
|
||||
|
||||
/* read from the sensor */
|
||||
uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0};
|
||||
uint8_t val[47] = { 0 };
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
ret = transfer(nullptr, 0, &val[0], 22);
|
||||
if (PX4FLOW_REG == 0x00) {
|
||||
ret = transfer(nullptr, 0, &val[0], 47); // read 47 bytes (22+25 : frame1 + frame2)
|
||||
}
|
||||
|
||||
if (PX4FLOW_REG == 0x16) {
|
||||
ret = transfer(nullptr, 0, &val[0], 25); // read 25 bytes (only frame2)
|
||||
}
|
||||
|
||||
if (ret < 0) {
|
||||
debug("error reading from sensor: %d", ret);
|
||||
@@ -469,36 +475,74 @@ PX4FLOW::collect()
|
||||
return ret;
|
||||
}
|
||||
|
||||
// f.frame_count = val[1] << 8 | val[0];
|
||||
// f.pixel_flow_x_sum= val[3] << 8 | val[2];
|
||||
// f.pixel_flow_y_sum= val[5] << 8 | val[4];
|
||||
// f.flow_comp_m_x= val[7] << 8 | val[6];
|
||||
// f.flow_comp_m_y= val[9] << 8 | val[8];
|
||||
// f.qual= val[11] << 8 | val[10];
|
||||
// f.gyro_x_rate= val[13] << 8 | val[12];
|
||||
// f.gyro_y_rate= val[15] << 8 | val[14];
|
||||
// f.gyro_z_rate= val[17] << 8 | val[16];
|
||||
// f.gyro_range= val[18];
|
||||
// f.sonar_timestamp= val[19];
|
||||
// f.ground_distance= val[21] << 8 | val[20];
|
||||
if (PX4FLOW_REG == 0) {
|
||||
f.frame_count = val[1] << 8 | val[0];
|
||||
f.pixel_flow_x_sum = val[3] << 8 | val[2];
|
||||
f.pixel_flow_y_sum = val[5] << 8 | val[4];
|
||||
f.flow_comp_m_x = val[7] << 8 | val[6];
|
||||
f.flow_comp_m_y = val[9] << 8 | val[8];
|
||||
f.qual = val[11] << 8 | val[10];
|
||||
f.gyro_x_rate = val[13] << 8 | val[12];
|
||||
f.gyro_y_rate = val[15] << 8 | val[14];
|
||||
f.gyro_z_rate = val[17] << 8 | val[16];
|
||||
f.gyro_range = val[18];
|
||||
f.sonar_timestamp = val[19];
|
||||
f.ground_distance = val[21] << 8 | val[20];
|
||||
|
||||
f_integral.frame_count_since_last_readout = val[23] << 8 | val[22];
|
||||
f_integral.pixel_flow_x_integral = val[25] << 8 | val[24];
|
||||
f_integral.pixel_flow_y_integral = val[27] << 8 | val[26];
|
||||
f_integral.gyro_x_rate_integral = val[29] << 8 | val[28];
|
||||
f_integral.gyro_y_rate_integral = val[31] << 8 | val[30];
|
||||
f_integral.gyro_z_rate_integral = val[33] << 8 | val[32];
|
||||
f_integral.integration_timespan = val[37] << 24 | val[36] << 16
|
||||
| val[35] << 8 | val[34];
|
||||
f_integral.time_since_last_sonar_update = val[41] << 24 | val[40] << 16
|
||||
| val[39] << 8 | val[38];
|
||||
f_integral.ground_distance = val[43] << 8 | val[42];
|
||||
f_integral.gyro_temperature = val[45] << 8 | val[44];
|
||||
f_integral.qual = val[46];
|
||||
}
|
||||
|
||||
if (PX4FLOW_REG == 0x16) {
|
||||
f_integral.frame_count_since_last_readout = val[1] << 8 | val[0];
|
||||
f_integral.pixel_flow_x_integral = val[3] << 8 | val[2];
|
||||
f_integral.pixel_flow_y_integral = val[5] << 8 | val[4];
|
||||
f_integral.gyro_x_rate_integral = val[7] << 8 | val[6];
|
||||
f_integral.gyro_y_rate_integral = val[9] << 8 | val[8];
|
||||
f_integral.gyro_z_rate_integral = val[11] << 8 | val[10];
|
||||
f_integral.integration_timespan = val[15] << 24 | val[14] << 16 | val[13] << 8 | val[12];
|
||||
f_integral.time_since_last_sonar_update = val[19] << 24 | val[18] << 16 | val[17] << 8 | val[16];
|
||||
f_integral.ground_distance = val[21] << 8 | val[20];
|
||||
f_integral.gyro_temperature = val[23] << 8 | val[22];
|
||||
f_integral.qual = val[24];
|
||||
}
|
||||
|
||||
int16_t flowcx = val[7] << 8 | val[6];
|
||||
int16_t flowcy = val[9] << 8 | val[8];
|
||||
int16_t gdist = val[21] << 8 | val[20];
|
||||
|
||||
struct optical_flow_s report;
|
||||
report.flow_comp_x_m = float(flowcx) / 1000.0f;
|
||||
report.flow_comp_y_m = float(flowcy) / 1000.0f;
|
||||
report.flow_raw_x = val[3] << 8 | val[2];
|
||||
report.flow_raw_y = val[5] << 8 | val[4];
|
||||
report.ground_distance_m = float(gdist) / 1000.0f;
|
||||
report.quality = val[10];
|
||||
report.sensor_id = 0;
|
||||
|
||||
report.timestamp = hrt_absolute_time();
|
||||
report.pixel_flow_x_integral = static_cast<float>(f_integral.pixel_flow_x_integral) / 10000.0f;//convert to radians
|
||||
report.pixel_flow_y_integral = static_cast<float>(f_integral.pixel_flow_y_integral) / 10000.0f;//convert to radians
|
||||
report.frame_count_since_last_readout = f_integral.frame_count_since_last_readout;
|
||||
report.ground_distance_m = static_cast<float>(f_integral.ground_distance) / 1000.0f;//convert to meters
|
||||
report.quality = f_integral.qual; //0:bad ; 255 max quality
|
||||
report.gyro_x_rate_integral = static_cast<float>(f_integral.gyro_x_rate_integral) / 10000.0f; //convert to radians
|
||||
report.gyro_y_rate_integral = static_cast<float>(f_integral.gyro_y_rate_integral) / 10000.0f; //convert to radians
|
||||
report.gyro_z_rate_integral = static_cast<float>(f_integral.gyro_z_rate_integral) / 10000.0f; //convert to radians
|
||||
report.integration_timespan = f_integral.integration_timespan; //microseconds
|
||||
report.time_since_last_sonar_update = f_integral.time_since_last_sonar_update;//microseconds
|
||||
report.gyro_temperature = f_integral.gyro_temperature;//Temperature * 100 in centi-degrees Celsius
|
||||
|
||||
report.sensor_id = 0;
|
||||
|
||||
/* publish it */
|
||||
orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
|
||||
if (_px4flow_topic < 0) {
|
||||
_px4flow_topic = orb_advertise(ORB_ID(optical_flow), &report);
|
||||
|
||||
} else {
|
||||
/* publish it */
|
||||
orb_publish(ORB_ID(optical_flow), _px4flow_topic, &report);
|
||||
}
|
||||
|
||||
/* post a report to the ring */
|
||||
if (_reports->force(&report)) {
|
||||
@@ -558,50 +602,21 @@ PX4FLOW::cycle_trampoline(void *arg)
|
||||
void
|
||||
PX4FLOW::cycle()
|
||||
{
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
debug("collection error");
|
||||
/* restart the measurement state machine */
|
||||
start();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
|
||||
/*
|
||||
* Is there a collect->measure gap?
|
||||
*/
|
||||
if (_measure_ticks > USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) {
|
||||
|
||||
/* schedule a fresh cycle call when we are ready to measure again */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&PX4FLOW::cycle_trampoline,
|
||||
this,
|
||||
_measure_ticks - USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
if (OK != measure()) {
|
||||
debug("measure error");
|
||||
}
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
debug("collection error");
|
||||
/* restart the measurement state machine */
|
||||
start();
|
||||
return;
|
||||
}
|
||||
|
||||
work_queue(HPWORK, &_work, (worker_t)&PX4FLOW::cycle_trampoline, this,
|
||||
_measure_ticks);
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&PX4FLOW::cycle_trampoline,
|
||||
this,
|
||||
USEC2TICK(PX4FLOW_CONVERSION_INTERVAL));
|
||||
}
|
||||
|
||||
void
|
||||
@@ -647,14 +662,41 @@ start()
|
||||
}
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new PX4FLOW(PX4FLOW_BUS);
|
||||
g_dev = new PX4FLOW(PX4_I2C_BUS_EXPANSION);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (OK != g_dev->init()) {
|
||||
goto fail;
|
||||
|
||||
#ifdef PX4_I2C_BUS_ESC
|
||||
delete g_dev;
|
||||
/* try 2nd bus */
|
||||
g_dev = new PX4FLOW(PX4_I2C_BUS_ESC);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (OK != g_dev->init()) {
|
||||
#endif
|
||||
|
||||
delete g_dev;
|
||||
/* try 3rd bus */
|
||||
g_dev = new PX4FLOW(PX4_I2C_BUS_ONBOARD);
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (OK != g_dev->init()) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
#ifdef PX4_I2C_BUS_ESC
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
@@ -683,7 +725,8 @@ fail:
|
||||
/**
|
||||
* Stop the driver
|
||||
*/
|
||||
void stop()
|
||||
void
|
||||
stop()
|
||||
{
|
||||
if (g_dev != nullptr) {
|
||||
delete g_dev;
|
||||
@@ -714,6 +757,7 @@ test()
|
||||
err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH);
|
||||
}
|
||||
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
@@ -723,18 +767,18 @@ test()
|
||||
}
|
||||
|
||||
warnx("single read");
|
||||
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
|
||||
warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
|
||||
warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
|
||||
warnx("framecount_integral: %u",
|
||||
f_integral.frame_count_since_last_readout);
|
||||
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
|
||||
errx(1, "failed to set 2Hz poll rate");
|
||||
/* start the sensor polling at 10Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 10)) {
|
||||
errx(1, "failed to set 10Hz poll rate");
|
||||
}
|
||||
|
||||
/* read the sensor 5x and report each value */
|
||||
for (unsigned i = 0; i < 5; i++) {
|
||||
for (unsigned i = 0; i < 10; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
@@ -754,9 +798,22 @@ test()
|
||||
}
|
||||
|
||||
warnx("periodic read %u", i);
|
||||
warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m);
|
||||
warnx("flowy: %0.2f m/s", (double)report.flow_comp_y_m);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
|
||||
warnx("framecount_total: %u", f.frame_count);
|
||||
warnx("framecount_integral: %u",
|
||||
f_integral.frame_count_since_last_readout);
|
||||
warnx("pixel_flow_x_integral: %i", f_integral.pixel_flow_x_integral);
|
||||
warnx("pixel_flow_y_integral: %i", f_integral.pixel_flow_y_integral);
|
||||
warnx("gyro_x_rate_integral: %i", f_integral.gyro_x_rate_integral);
|
||||
warnx("gyro_y_rate_integral: %i", f_integral.gyro_y_rate_integral);
|
||||
warnx("gyro_z_rate_integral: %i", f_integral.gyro_z_rate_integral);
|
||||
warnx("integration_timespan [us]: %u", f_integral.integration_timespan);
|
||||
warnx("ground_distance: %0.2f m",
|
||||
(double) f_integral.ground_distance / 1000);
|
||||
warnx("time since last sonar update [us]: %i",
|
||||
f_integral.time_since_last_sonar_update);
|
||||
warnx("quality integration average : %i", f_integral.qual);
|
||||
warnx("quality : %i", f.qual);
|
||||
|
||||
|
||||
}
|
||||
|
||||
+52
-45
@@ -817,6 +817,11 @@ PX4IO::init()
|
||||
|
||||
}
|
||||
|
||||
/* set safety to off if circuit breaker enabled */
|
||||
if (circuit_breaker_enabled("CBRK_IO_SAFETY", CBRK_IO_SAFETY_KEY)) {
|
||||
(void)io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC);
|
||||
}
|
||||
|
||||
/* try to claim the generic PWM output device node as well - it's OK if we fail at this */
|
||||
ret = register_driver(PWM_OUTPUT_DEVICE_PATH, &fops, 0666, (void *)this);
|
||||
|
||||
@@ -1155,52 +1160,54 @@ PX4IO::io_set_arming_state()
|
||||
actuator_armed_s armed; ///< system armed state
|
||||
vehicle_control_mode_s control_mode; ///< vehicle_control_mode
|
||||
|
||||
orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
|
||||
orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
|
||||
int have_armed = orb_copy(ORB_ID(actuator_armed), _t_actuator_armed, &armed);
|
||||
int have_control_mode = orb_copy(ORB_ID(vehicle_control_mode), _t_vehicle_control_mode, &control_mode);
|
||||
|
||||
uint16_t set = 0;
|
||||
uint16_t clear = 0;
|
||||
|
||||
if (armed.armed) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||
if (have_armed == OK) {
|
||||
if (armed.armed) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||
}
|
||||
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_FMU_ARMED;
|
||||
if (armed.lockdown && !_lockdown_override) {
|
||||
set |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
|
||||
}
|
||||
|
||||
/* Do not set failsafe if circuit breaker is enabled */
|
||||
if (armed.force_failsafe && !_cb_flighttermination) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
}
|
||||
|
||||
// XXX this is for future support in the commander
|
||||
// but can be removed if unneeded
|
||||
// if (armed.termination_failsafe) {
|
||||
// set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// } else {
|
||||
// clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// }
|
||||
|
||||
if (armed.ready_to_arm) {
|
||||
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||
}
|
||||
}
|
||||
|
||||
if (armed.lockdown && !_lockdown_override) {
|
||||
set |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN;
|
||||
}
|
||||
|
||||
/* Do not set failsafe if circuit breaker is enabled */
|
||||
if (armed.force_failsafe && !_cb_flighttermination) {
|
||||
set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE;
|
||||
}
|
||||
|
||||
// XXX this is for future support in the commander
|
||||
// but can be removed if unneeded
|
||||
// if (armed.termination_failsafe) {
|
||||
// set |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// } else {
|
||||
// clear |= PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE;
|
||||
// }
|
||||
|
||||
if (armed.ready_to_arm) {
|
||||
set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_IO_ARM_OK;
|
||||
}
|
||||
|
||||
if (control_mode.flag_external_manual_override_ok) {
|
||||
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||
if (have_control_mode == OK) {
|
||||
if (control_mode.flag_external_manual_override_ok) {
|
||||
set |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||
} else {
|
||||
clear |= PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK;
|
||||
}
|
||||
}
|
||||
|
||||
return io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, clear, set);
|
||||
@@ -2193,7 +2200,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||
if (pwm->channel_count > _max_actuators)
|
||||
/* fail with error */
|
||||
return E2BIG;
|
||||
return -E2BIG;
|
||||
|
||||
/* copy values to registers in IO */
|
||||
ret = io_reg_set(PX4IO_PAGE_FAILSAFE_PWM, 0, pwm->values, pwm->channel_count);
|
||||
@@ -2212,7 +2219,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||
if (pwm->channel_count > _max_actuators)
|
||||
/* fail with error */
|
||||
return E2BIG;
|
||||
return -E2BIG;
|
||||
|
||||
/* copy values to registers in IO */
|
||||
ret = io_reg_set(PX4IO_PAGE_DISARMED_PWM, 0, pwm->values, pwm->channel_count);
|
||||
@@ -2231,7 +2238,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||
if (pwm->channel_count > _max_actuators)
|
||||
/* fail with error */
|
||||
return E2BIG;
|
||||
return -E2BIG;
|
||||
|
||||
/* copy values to registers in IO */
|
||||
ret = io_reg_set(PX4IO_PAGE_CONTROL_MIN_PWM, 0, pwm->values, pwm->channel_count);
|
||||
@@ -2250,7 +2257,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
||||
struct pwm_output_values* pwm = (struct pwm_output_values*)arg;
|
||||
if (pwm->channel_count > _max_actuators)
|
||||
/* fail with error */
|
||||
return E2BIG;
|
||||
return -E2BIG;
|
||||
|
||||
/* copy values to registers in IO */
|
||||
ret = io_reg_set(PX4IO_PAGE_CONTROL_MAX_PWM, 0, pwm->values, pwm->channel_count);
|
||||
@@ -2587,9 +2594,9 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg)
|
||||
on param_get()
|
||||
*/
|
||||
struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg;
|
||||
if (config->channel >= _max_actuators) {
|
||||
if (config->channel >= RC_INPUT_MAX_CHANNELS) {
|
||||
/* fail with error */
|
||||
return E2BIG;
|
||||
return -E2BIG;
|
||||
}
|
||||
|
||||
/* copy values to registers in IO */
|
||||
|
||||
@@ -121,7 +121,7 @@ private:
|
||||
/* for now, we only support one RGBLED */
|
||||
namespace
|
||||
{
|
||||
RGBLED *g_rgbled;
|
||||
RGBLED *g_rgbled = nullptr;
|
||||
}
|
||||
|
||||
void rgbled_usage();
|
||||
@@ -680,15 +680,15 @@ rgbled_main(int argc, char *argv[])
|
||||
|
||||
ret = ioctl(fd, RGBLED_SET_MODE, (unsigned long)RGBLED_MODE_OFF);
|
||||
close(fd);
|
||||
/* delete the rgbled object if stop was requested, in addition to turning off the LED. */
|
||||
if (!strcmp(verb, "stop")) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
exit(0);
|
||||
}
|
||||
exit(ret);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "stop")) {
|
||||
delete g_rgbled;
|
||||
g_rgbled = nullptr;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(verb, "rgb")) {
|
||||
if (argc < 5) {
|
||||
errx(1, "Usage: rgbled rgb <red> <green> <blue>");
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
# 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
|
||||
@@ -32,10 +32,13 @@
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Build flow speed control
|
||||
# Makefile to build the TeraRanger One range finder driver
|
||||
#
|
||||
|
||||
MODULE_COMMAND = flow_speed_control
|
||||
MODULE_COMMAND = trone
|
||||
|
||||
SRCS = flow_speed_control_main.c \
|
||||
flow_speed_control_params.c
|
||||
SRCS = trone.cpp
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
@@ -0,0 +1,913 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file trone.cpp
|
||||
* @author Luis Rodrigues
|
||||
*
|
||||
* Driver for the TeraRanger One range finders connected via I2C.
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <drivers/device/i2c.h>
|
||||
|
||||
#include <sys/types.h>
|
||||
#include <stdint.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <semaphore.h>
|
||||
#include <string.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/wqueue.h>
|
||||
#include <nuttx/clock.h>
|
||||
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_range_finder.h>
|
||||
#include <drivers/device/ringbuffer.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/subsystem_info.h>
|
||||
|
||||
#include <board_config.h>
|
||||
|
||||
/* Configuration Constants */
|
||||
#define TRONE_BUS PX4_I2C_BUS_EXPANSION
|
||||
#define TRONE_BASEADDR 0x30 /* 7-bit address */
|
||||
#define TRONE_DEVICE_PATH "/dev/trone"
|
||||
|
||||
/* TRONE Registers addresses */
|
||||
|
||||
#define TRONE_MEASURE_REG 0x00 /* Measure range register */
|
||||
|
||||
/* Device limits */
|
||||
#define TRONE_MIN_DISTANCE (0.20f)
|
||||
#define TRONE_MAX_DISTANCE (14.00f)
|
||||
|
||||
#define TRONE_CONVERSION_INTERVAL 50000 /* 50ms */
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
static const int ERROR = -1;
|
||||
|
||||
#ifndef CONFIG_SCHED_WORKQUEUE
|
||||
# error This requires CONFIG_SCHED_WORKQUEUE.
|
||||
#endif
|
||||
|
||||
class TRONE : public device::I2C
|
||||
{
|
||||
public:
|
||||
TRONE(int bus = TRONE_BUS, int address = TRONE_BASEADDR);
|
||||
virtual ~TRONE();
|
||||
|
||||
virtual int init();
|
||||
|
||||
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
|
||||
|
||||
/**
|
||||
* Diagnostics - print some basic information about the driver.
|
||||
*/
|
||||
void print_info();
|
||||
|
||||
protected:
|
||||
virtual int probe();
|
||||
|
||||
private:
|
||||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
int _class_instance;
|
||||
|
||||
orb_advert_t _range_finder_topic;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
perf_counter_t _buffer_overflows;
|
||||
|
||||
/**
|
||||
* Test whether the device supported by the driver is present at a
|
||||
* specific address.
|
||||
*
|
||||
* @param address The I2C bus address to probe.
|
||||
* @return True if the device is present.
|
||||
*/
|
||||
int probe_address(uint8_t address);
|
||||
|
||||
/**
|
||||
* Initialise the automatic measurement state machine and start it.
|
||||
*
|
||||
* @note This function is called at open and error time. It might make sense
|
||||
* to make it more aggressive about resetting the bus in case of errors.
|
||||
*/
|
||||
void start();
|
||||
|
||||
/**
|
||||
* Stop the automatic measurement state machine.
|
||||
*/
|
||||
void stop();
|
||||
|
||||
/**
|
||||
* Set the min and max distance thresholds if you want the end points of the sensors
|
||||
* range to be brought in at all, otherwise it will use the defaults TRONE_MIN_DISTANCE
|
||||
* and TRONE_MAX_DISTANCE
|
||||
*/
|
||||
void set_minimum_distance(float min);
|
||||
void set_maximum_distance(float max);
|
||||
float get_minimum_distance();
|
||||
float get_maximum_distance();
|
||||
|
||||
/**
|
||||
* Perform a poll cycle; collect from the previous measurement
|
||||
* and start a new one.
|
||||
*/
|
||||
void cycle();
|
||||
int measure();
|
||||
int collect();
|
||||
/**
|
||||
* Static trampoline from the workq context; because we don't have a
|
||||
* generic workq wrapper yet.
|
||||
*
|
||||
* @param arg Instance pointer for the driver that is polling.
|
||||
*/
|
||||
static void cycle_trampoline(void *arg);
|
||||
|
||||
|
||||
};
|
||||
|
||||
static const uint8_t crc_table[] = {
|
||||
0x00, 0x07, 0x0e, 0x09, 0x1c, 0x1b, 0x12, 0x15, 0x38, 0x3f, 0x36, 0x31,
|
||||
0x24, 0x23, 0x2a, 0x2d, 0x70, 0x77, 0x7e, 0x79, 0x6c, 0x6b, 0x62, 0x65,
|
||||
0x48, 0x4f, 0x46, 0x41, 0x54, 0x53, 0x5a, 0x5d, 0xe0, 0xe7, 0xee, 0xe9,
|
||||
0xfc, 0xfb, 0xf2, 0xf5, 0xd8, 0xdf, 0xd6, 0xd1, 0xc4, 0xc3, 0xca, 0xcd,
|
||||
0x90, 0x97, 0x9e, 0x99, 0x8c, 0x8b, 0x82, 0x85, 0xa8, 0xaf, 0xa6, 0xa1,
|
||||
0xb4, 0xb3, 0xba, 0xbd, 0xc7, 0xc0, 0xc9, 0xce, 0xdb, 0xdc, 0xd5, 0xd2,
|
||||
0xff, 0xf8, 0xf1, 0xf6, 0xe3, 0xe4, 0xed, 0xea, 0xb7, 0xb0, 0xb9, 0xbe,
|
||||
0xab, 0xac, 0xa5, 0xa2, 0x8f, 0x88, 0x81, 0x86, 0x93, 0x94, 0x9d, 0x9a,
|
||||
0x27, 0x20, 0x29, 0x2e, 0x3b, 0x3c, 0x35, 0x32, 0x1f, 0x18, 0x11, 0x16,
|
||||
0x03, 0x04, 0x0d, 0x0a, 0x57, 0x50, 0x59, 0x5e, 0x4b, 0x4c, 0x45, 0x42,
|
||||
0x6f, 0x68, 0x61, 0x66, 0x73, 0x74, 0x7d, 0x7a, 0x89, 0x8e, 0x87, 0x80,
|
||||
0x95, 0x92, 0x9b, 0x9c, 0xb1, 0xb6, 0xbf, 0xb8, 0xad, 0xaa, 0xa3, 0xa4,
|
||||
0xf9, 0xfe, 0xf7, 0xf0, 0xe5, 0xe2, 0xeb, 0xec, 0xc1, 0xc6, 0xcf, 0xc8,
|
||||
0xdd, 0xda, 0xd3, 0xd4, 0x69, 0x6e, 0x67, 0x60, 0x75, 0x72, 0x7b, 0x7c,
|
||||
0x51, 0x56, 0x5f, 0x58, 0x4d, 0x4a, 0x43, 0x44, 0x19, 0x1e, 0x17, 0x10,
|
||||
0x05, 0x02, 0x0b, 0x0c, 0x21, 0x26, 0x2f, 0x28, 0x3d, 0x3a, 0x33, 0x34,
|
||||
0x4e, 0x49, 0x40, 0x47, 0x52, 0x55, 0x5c, 0x5b, 0x76, 0x71, 0x78, 0x7f,
|
||||
0x6a, 0x6d, 0x64, 0x63, 0x3e, 0x39, 0x30, 0x37, 0x22, 0x25, 0x2c, 0x2b,
|
||||
0x06, 0x01, 0x08, 0x0f, 0x1a, 0x1d, 0x14, 0x13, 0xae, 0xa9, 0xa0, 0xa7,
|
||||
0xb2, 0xb5, 0xbc, 0xbb, 0x96, 0x91, 0x98, 0x9f, 0x8a, 0x8d, 0x84, 0x83,
|
||||
0xde, 0xd9, 0xd0, 0xd7, 0xc2, 0xc5, 0xcc, 0xcb, 0xe6, 0xe1, 0xe8, 0xef,
|
||||
0xfa, 0xfd, 0xf4, 0xf3
|
||||
};
|
||||
|
||||
uint8_t crc8(uint8_t *p, uint8_t len){
|
||||
uint16_t i;
|
||||
uint16_t crc = 0x0;
|
||||
|
||||
while (len--) {
|
||||
i = (crc ^ *p++) & 0xFF;
|
||||
crc = (crc_table[i] ^ (crc << 8)) & 0xFF;
|
||||
}
|
||||
|
||||
return crc & 0xFF;
|
||||
}
|
||||
|
||||
/*
|
||||
* Driver 'main' command.
|
||||
*/
|
||||
extern "C" __EXPORT int trone_main(int argc, char *argv[]);
|
||||
|
||||
TRONE::TRONE(int bus, int address) :
|
||||
I2C("TRONE", TRONE_DEVICE_PATH, bus, address, 100000),
|
||||
_min_distance(TRONE_MIN_DISTANCE),
|
||||
_max_distance(TRONE_MAX_DISTANCE),
|
||||
_reports(nullptr),
|
||||
_sensor_ok(false),
|
||||
_measure_ticks(0),
|
||||
_collect_phase(false),
|
||||
_class_instance(-1),
|
||||
_range_finder_topic(-1),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "trone_read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, "trone_comms_errors")),
|
||||
_buffer_overflows(perf_alloc(PC_COUNT, "trone_buffer_overflows"))
|
||||
{
|
||||
// up the retries since the device misses the first measure attempts
|
||||
I2C::_retries = 3;
|
||||
|
||||
// enable debug() calls
|
||||
_debug_enabled = false;
|
||||
|
||||
// work_cancel in the dtor will explode if we don't do this...
|
||||
memset(&_work, 0, sizeof(_work));
|
||||
}
|
||||
|
||||
TRONE::~TRONE()
|
||||
{
|
||||
/* make sure we are truly inactive */
|
||||
stop();
|
||||
|
||||
/* free any existing reports */
|
||||
if (_reports != nullptr) {
|
||||
delete _reports;
|
||||
}
|
||||
|
||||
if (_class_instance != -1) {
|
||||
unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance);
|
||||
}
|
||||
|
||||
// free perf counters
|
||||
perf_free(_sample_perf);
|
||||
perf_free(_comms_errors);
|
||||
perf_free(_buffer_overflows);
|
||||
}
|
||||
|
||||
int
|
||||
TRONE::init()
|
||||
{
|
||||
int ret = ERROR;
|
||||
|
||||
/* do I2C init (and probe) first */
|
||||
if (I2C::init() != OK) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
/* allocate basic report buffers */
|
||||
_reports = new RingBuffer(2, sizeof(range_finder_report));
|
||||
|
||||
if (_reports == nullptr) {
|
||||
goto out;
|
||||
}
|
||||
|
||||
_class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH);
|
||||
|
||||
if (_class_instance == CLASS_DEVICE_PRIMARY) {
|
||||
/* get a publish handle on the range finder topic */
|
||||
struct range_finder_report rf_report;
|
||||
measure();
|
||||
_reports->get(&rf_report);
|
||||
_range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report);
|
||||
|
||||
if (_range_finder_topic < 0) {
|
||||
debug("failed to create sensor_range_finder object. Did you start uOrb?");
|
||||
}
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
/* sensor is ok, but we don't really know if it is within range */
|
||||
_sensor_ok = true;
|
||||
out:
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
TRONE::probe()
|
||||
{
|
||||
return measure();
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::set_minimum_distance(float min)
|
||||
{
|
||||
_min_distance = min;
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::set_maximum_distance(float max)
|
||||
{
|
||||
_max_distance = max;
|
||||
}
|
||||
|
||||
float
|
||||
TRONE::get_minimum_distance()
|
||||
{
|
||||
return _min_distance;
|
||||
}
|
||||
|
||||
float
|
||||
TRONE::get_maximum_distance()
|
||||
{
|
||||
return _max_distance;
|
||||
}
|
||||
|
||||
int
|
||||
TRONE::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
|
||||
case SENSORIOCSPOLLRATE: {
|
||||
switch (arg) {
|
||||
|
||||
/* switching to manual polling */
|
||||
case SENSOR_POLLRATE_MANUAL:
|
||||
stop();
|
||||
_measure_ticks = 0;
|
||||
return OK;
|
||||
|
||||
/* external signalling (DRDY) not supported */
|
||||
case SENSOR_POLLRATE_EXTERNAL:
|
||||
|
||||
/* zero would be bad */
|
||||
case 0:
|
||||
return -EINVAL;
|
||||
|
||||
/* set default/max polling rate */
|
||||
case SENSOR_POLLRATE_MAX:
|
||||
case SENSOR_POLLRATE_DEFAULT: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* set interval for next measurement to minimum legal value */
|
||||
_measure_ticks = USEC2TICK(TRONE_CONVERSION_INTERVAL);
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start) {
|
||||
start();
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/* adjust to a legal polling interval in Hz */
|
||||
default: {
|
||||
/* do we need to start internal polling? */
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* convert hz to tick interval via microseconds */
|
||||
unsigned ticks = USEC2TICK(1000000 / arg);
|
||||
|
||||
/* check against maximum rate */
|
||||
if (ticks < USEC2TICK(TRONE_CONVERSION_INTERVAL)) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* update interval for next measurement */
|
||||
_measure_ticks = ticks;
|
||||
|
||||
/* if we need to start the poll state machine, do it */
|
||||
if (want_start) {
|
||||
start();
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
case SENSORIOCGPOLLRATE:
|
||||
if (_measure_ticks == 0) {
|
||||
return SENSOR_POLLRATE_MANUAL;
|
||||
}
|
||||
|
||||
return (1000 / _measure_ticks);
|
||||
|
||||
case SENSORIOCSQUEUEDEPTH: {
|
||||
/* lower bound is mandatory, upper bound is a sanity check */
|
||||
if ((arg < 1) || (arg > 100)) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
irqstate_t flags = irqsave();
|
||||
|
||||
if (!_reports->resize(arg)) {
|
||||
irqrestore(flags);
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
irqrestore(flags);
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
case SENSORIOCGQUEUEDEPTH:
|
||||
return _reports->size();
|
||||
|
||||
case SENSORIOCRESET:
|
||||
/* XXX implement this */
|
||||
return -EINVAL;
|
||||
|
||||
case RANGEFINDERIOCSETMINIUMDISTANCE: {
|
||||
set_minimum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
|
||||
case RANGEFINDERIOCSETMAXIUMDISTANCE: {
|
||||
set_maximum_distance(*(float *)arg);
|
||||
return 0;
|
||||
}
|
||||
break;
|
||||
|
||||
default:
|
||||
/* give it to the superclass */
|
||||
return I2C::ioctl(filp, cmd, arg);
|
||||
}
|
||||
}
|
||||
|
||||
ssize_t
|
||||
TRONE::read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
unsigned count = buflen / sizeof(struct range_finder_report);
|
||||
struct range_finder_report *rbuf = reinterpret_cast<struct range_finder_report *>(buffer);
|
||||
int ret = 0;
|
||||
|
||||
/* buffer must be large enough */
|
||||
if (count < 1) {
|
||||
return -ENOSPC;
|
||||
}
|
||||
|
||||
/* if automatic measurement is enabled */
|
||||
if (_measure_ticks > 0) {
|
||||
|
||||
/*
|
||||
* While there is space in the caller's buffer, and reports, copy them.
|
||||
* Note that we may be pre-empted by the workq thread while we are doing this;
|
||||
* we are careful to avoid racing with them.
|
||||
*/
|
||||
while (count--) {
|
||||
if (_reports->get(rbuf)) {
|
||||
ret += sizeof(*rbuf);
|
||||
rbuf++;
|
||||
}
|
||||
}
|
||||
|
||||
/* if there was no data, warn the caller */
|
||||
return ret ? ret : -EAGAIN;
|
||||
}
|
||||
|
||||
/* manual measurement - run one conversion */
|
||||
do {
|
||||
_reports->flush();
|
||||
|
||||
/* trigger a measurement */
|
||||
if (OK != measure()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* wait for it to complete */
|
||||
usleep(TRONE_CONVERSION_INTERVAL);
|
||||
|
||||
/* run the collection phase */
|
||||
if (OK != collect()) {
|
||||
ret = -EIO;
|
||||
break;
|
||||
}
|
||||
|
||||
/* state machine will have generated a report, copy it out */
|
||||
if (_reports->get(rbuf)) {
|
||||
ret = sizeof(*rbuf);
|
||||
}
|
||||
|
||||
} while (0);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
TRONE::measure()
|
||||
{
|
||||
int ret;
|
||||
|
||||
/*
|
||||
* Send the command to begin a measurement.
|
||||
*/
|
||||
const uint8_t cmd = TRONE_MEASURE_REG;
|
||||
ret = transfer(&cmd, sizeof(cmd), nullptr, 0);
|
||||
|
||||
if (OK != ret) {
|
||||
perf_count(_comms_errors);
|
||||
log("i2c::transfer returned %d", ret);
|
||||
return ret;
|
||||
}
|
||||
|
||||
ret = OK;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
int
|
||||
TRONE::collect()
|
||||
{
|
||||
int ret = -EIO;
|
||||
|
||||
/* read from the sensor */
|
||||
uint8_t val[3] = {0, 0, 0};
|
||||
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
ret = transfer(nullptr, 0, &val[0], 3);
|
||||
|
||||
if (ret < 0) {
|
||||
log("error reading from sensor: %d", ret);
|
||||
perf_count(_comms_errors);
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
}
|
||||
|
||||
uint16_t distance = (val[0] << 8) | val[1];
|
||||
float si_units = distance * 0.001f; /* mm to m */
|
||||
struct range_finder_report report;
|
||||
|
||||
/* this should be fairly close to the end of the measurement, so the best approximation of the time */
|
||||
report.timestamp = hrt_absolute_time();
|
||||
report.error_count = perf_event_count(_comms_errors);
|
||||
report.distance = si_units;
|
||||
report.valid = crc8(val, 2) == val[2] && si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0;
|
||||
|
||||
|
||||
/* publish it, if we are the primary */
|
||||
if (_range_finder_topic >= 0) {
|
||||
orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report);
|
||||
}
|
||||
|
||||
if (_reports->force(&report)) {
|
||||
perf_count(_buffer_overflows);
|
||||
}
|
||||
|
||||
/* notify anyone waiting for data */
|
||||
poll_notify(POLLIN);
|
||||
|
||||
ret = OK;
|
||||
|
||||
perf_end(_sample_perf);
|
||||
return ret;
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::start()
|
||||
{
|
||||
/* reset the report ring and state machine */
|
||||
_collect_phase = false;
|
||||
_reports->flush();
|
||||
|
||||
/* schedule a cycle to start things */
|
||||
work_queue(HPWORK, &_work, (worker_t)&TRONE::cycle_trampoline, this, 1);
|
||||
|
||||
/* notify about state change */
|
||||
struct subsystem_info_s info = {
|
||||
true,
|
||||
true,
|
||||
true,
|
||||
SUBSYSTEM_TYPE_RANGEFINDER
|
||||
};
|
||||
static orb_advert_t pub = -1;
|
||||
|
||||
if (pub > 0) {
|
||||
orb_publish(ORB_ID(subsystem_info), pub, &info);
|
||||
|
||||
} else {
|
||||
pub = orb_advertise(ORB_ID(subsystem_info), &info);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::stop()
|
||||
{
|
||||
work_cancel(HPWORK, &_work);
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::cycle_trampoline(void *arg)
|
||||
{
|
||||
TRONE *dev = (TRONE *)arg;
|
||||
|
||||
dev->cycle();
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::cycle()
|
||||
{
|
||||
/* collection phase? */
|
||||
if (_collect_phase) {
|
||||
|
||||
/* perform collection */
|
||||
if (OK != collect()) {
|
||||
log("collection error");
|
||||
/* restart the measurement state machine */
|
||||
start();
|
||||
return;
|
||||
}
|
||||
|
||||
/* next phase is measurement */
|
||||
_collect_phase = false;
|
||||
|
||||
/*
|
||||
* Is there a collect->measure gap?
|
||||
*/
|
||||
if (_measure_ticks > USEC2TICK(TRONE_CONVERSION_INTERVAL)) {
|
||||
|
||||
/* schedule a fresh cycle call when we are ready to measure again */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&TRONE::cycle_trampoline,
|
||||
this,
|
||||
_measure_ticks - USEC2TICK(TRONE_CONVERSION_INTERVAL));
|
||||
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
/* measurement phase */
|
||||
if (OK != measure()) {
|
||||
log("measure error");
|
||||
}
|
||||
|
||||
/* next phase is collection */
|
||||
_collect_phase = true;
|
||||
|
||||
/* schedule a fresh cycle call when the measurement is done */
|
||||
work_queue(HPWORK,
|
||||
&_work,
|
||||
(worker_t)&TRONE::cycle_trampoline,
|
||||
this,
|
||||
USEC2TICK(TRONE_CONVERSION_INTERVAL));
|
||||
}
|
||||
|
||||
void
|
||||
TRONE::print_info()
|
||||
{
|
||||
perf_print_counter(_sample_perf);
|
||||
perf_print_counter(_comms_errors);
|
||||
perf_print_counter(_buffer_overflows);
|
||||
printf("poll interval: %u ticks\n", _measure_ticks);
|
||||
_reports->print_info("report queue");
|
||||
}
|
||||
|
||||
/**
|
||||
* Local functions in support of the shell command.
|
||||
*/
|
||||
namespace trone
|
||||
{
|
||||
|
||||
/* oddly, ERROR is not defined for c++ */
|
||||
#ifdef ERROR
|
||||
# undef ERROR
|
||||
#endif
|
||||
const int ERROR = -1;
|
||||
|
||||
TRONE *g_dev;
|
||||
|
||||
void start();
|
||||
void stop();
|
||||
void test();
|
||||
void reset();
|
||||
void info();
|
||||
|
||||
/**
|
||||
* Start the driver.
|
||||
*/
|
||||
void
|
||||
start()
|
||||
{
|
||||
int fd;
|
||||
|
||||
if (g_dev != nullptr) {
|
||||
errx(1, "already started");
|
||||
}
|
||||
|
||||
/* create the driver */
|
||||
g_dev = new TRONE(TRONE_BUS);
|
||||
|
||||
|
||||
if (g_dev == nullptr) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (OK != g_dev->init()) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
/* set the poll rate to default, starts automatic data collection */
|
||||
fd = open(TRONE_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
goto fail;
|
||||
}
|
||||
|
||||
exit(0);
|
||||
|
||||
fail:
|
||||
|
||||
if (g_dev != nullptr) {
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
}
|
||||
|
||||
errx(1, "driver start failed");
|
||||
}
|
||||
|
||||
/**
|
||||
* Stop the driver
|
||||
*/
|
||||
void stop()
|
||||
{
|
||||
if (g_dev != nullptr) {
|
||||
delete g_dev;
|
||||
g_dev = nullptr;
|
||||
|
||||
} else {
|
||||
errx(1, "driver not running");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Perform some basic functional tests on the driver;
|
||||
* make sure we can collect data from the sensor in polled
|
||||
* and automatic modes.
|
||||
*/
|
||||
void
|
||||
test()
|
||||
{
|
||||
struct range_finder_report report;
|
||||
ssize_t sz;
|
||||
int ret;
|
||||
|
||||
int fd = open(TRONE_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
err(1, "%s open failed (try 'trone start' if the driver is not running", TRONE_DEVICE_PATH);
|
||||
}
|
||||
|
||||
/* do a simple demand read */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
err(1, "immediate read failed");
|
||||
}
|
||||
|
||||
warnx("single read");
|
||||
warnx("measurement: %0.2f m", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
|
||||
/* start the sensor polling at 2Hz */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) {
|
||||
errx(1, "failed to set 2Hz poll rate");
|
||||
}
|
||||
|
||||
/* read the sensor 50x and report each value */
|
||||
for (unsigned i = 0; i < 50; i++) {
|
||||
struct pollfd fds;
|
||||
|
||||
/* wait for data to be ready */
|
||||
fds.fd = fd;
|
||||
fds.events = POLLIN;
|
||||
ret = poll(&fds, 1, 2000);
|
||||
|
||||
if (ret != 1) {
|
||||
errx(1, "timed out waiting for sensor data");
|
||||
}
|
||||
|
||||
/* now go get it */
|
||||
sz = read(fd, &report, sizeof(report));
|
||||
|
||||
if (sz != sizeof(report)) {
|
||||
err(1, "periodic read failed");
|
||||
}
|
||||
|
||||
warnx("periodic read %u", i);
|
||||
warnx("valid %u", report.valid);
|
||||
warnx("measurement: %0.3f", (double)report.distance);
|
||||
warnx("time: %lld", report.timestamp);
|
||||
}
|
||||
|
||||
/* reset the sensor polling to default rate */
|
||||
if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) {
|
||||
errx(1, "failed to set default poll rate");
|
||||
}
|
||||
|
||||
errx(0, "PASS");
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the driver.
|
||||
*/
|
||||
void
|
||||
reset()
|
||||
{
|
||||
int fd = open(TRONE_DEVICE_PATH, O_RDONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
err(1, "failed ");
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
|
||||
err(1, "driver reset failed");
|
||||
}
|
||||
|
||||
if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) {
|
||||
err(1, "driver poll restart failed");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Print a little info about the driver.
|
||||
*/
|
||||
void
|
||||
info()
|
||||
{
|
||||
if (g_dev == nullptr) {
|
||||
errx(1, "driver not running");
|
||||
}
|
||||
|
||||
printf("state @ %p\n", g_dev);
|
||||
g_dev->print_info();
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
} // namespace
|
||||
|
||||
int
|
||||
trone_main(int argc, char *argv[])
|
||||
{
|
||||
/*
|
||||
* Start/load the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "start")) {
|
||||
trone::start();
|
||||
}
|
||||
|
||||
/*
|
||||
* Stop the driver
|
||||
*/
|
||||
if (!strcmp(argv[1], "stop")) {
|
||||
trone::stop();
|
||||
}
|
||||
|
||||
/*
|
||||
* Test the driver/device.
|
||||
*/
|
||||
if (!strcmp(argv[1], "test")) {
|
||||
trone::test();
|
||||
}
|
||||
|
||||
/*
|
||||
* Reset the driver.
|
||||
*/
|
||||
if (!strcmp(argv[1], "reset")) {
|
||||
trone::reset();
|
||||
}
|
||||
|
||||
/*
|
||||
* Print driver information.
|
||||
*/
|
||||
if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) {
|
||||
trone::info();
|
||||
}
|
||||
|
||||
errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'");
|
||||
}
|
||||
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2013, 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
|
||||
@@ -31,6 +30,7 @@
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file main.c
|
||||
*
|
||||
@@ -55,7 +55,7 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_global_position.h>
|
||||
#include <uORB/topics/vehicle_global_position_setpoint.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
@@ -106,11 +106,9 @@ static void usage(const char *reason);
|
||||
*
|
||||
* @param att_sp The current attitude setpoint - the values the system would like to reach.
|
||||
* @param att The current attitude. The controller should make the attitude match the setpoint
|
||||
* @param speed_body The velocity of the system. Currently unused.
|
||||
* @param rates_sp The angular rate setpoint. This is the output of the controller.
|
||||
*/
|
||||
void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att,
|
||||
float speed_body[], struct vehicle_rates_setpoint_s *rates_sp,
|
||||
void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp,
|
||||
struct actuator_controls_s *actuators);
|
||||
|
||||
/**
|
||||
@@ -125,7 +123,7 @@ void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const st
|
||||
* @param att The current attitude
|
||||
* @param att_sp The attitude setpoint. This is the output of the controller
|
||||
*/
|
||||
void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp,
|
||||
void control_heading(const struct vehicle_global_position_s *pos, const struct position_setpoint_s *sp,
|
||||
const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp);
|
||||
|
||||
/* Variables */
|
||||
@@ -135,8 +133,7 @@ static int deamon_task; /**< Handle of deamon task / thread */
|
||||
static struct params p;
|
||||
static struct param_handles ph;
|
||||
|
||||
void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att,
|
||||
float speed_body[], struct vehicle_rates_setpoint_s *rates_sp,
|
||||
void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const struct vehicle_attitude_s *att, struct vehicle_rates_setpoint_s *rates_sp,
|
||||
struct actuator_controls_s *actuators)
|
||||
{
|
||||
|
||||
@@ -173,7 +170,7 @@ void control_attitude(const struct vehicle_attitude_setpoint_s *att_sp, const st
|
||||
actuators->control[1] = pitch_err * p.pitch_p;
|
||||
}
|
||||
|
||||
void control_heading(const struct vehicle_global_position_s *pos, const struct vehicle_global_position_setpoint_s *sp,
|
||||
void control_heading(const struct vehicle_global_position_s *pos, const struct position_setpoint_s *sp,
|
||||
const struct vehicle_attitude_s *att, struct vehicle_attitude_setpoint_s *att_sp)
|
||||
{
|
||||
|
||||
@@ -186,7 +183,7 @@ void control_heading(const struct vehicle_global_position_s *pos, const struct v
|
||||
/* calculate heading error */
|
||||
float yaw_err = att->yaw - bearing;
|
||||
/* apply control gain */
|
||||
float roll_command = yaw_err * p.hdng_p;
|
||||
att_sp->roll_body = yaw_err * p.hdng_p;
|
||||
|
||||
/* limit output, this commonly is a tuning parameter, too */
|
||||
if (att_sp->roll_body < -0.6f) {
|
||||
@@ -253,7 +250,7 @@ int fixedwing_control_thread_main(int argc, char *argv[])
|
||||
memset(&manual_sp, 0, sizeof(manual_sp));
|
||||
struct vehicle_status_s vstatus;
|
||||
memset(&vstatus, 0, sizeof(vstatus));
|
||||
struct vehicle_global_position_setpoint_s global_sp;
|
||||
struct position_setpoint_s global_sp;
|
||||
memset(&global_sp, 0, sizeof(global_sp));
|
||||
|
||||
/* output structs - this is what is sent to the mixer */
|
||||
@@ -275,17 +272,14 @@ int fixedwing_control_thread_main(int argc, char *argv[])
|
||||
|
||||
/* subscribe to topics. */
|
||||
int att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
int global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
|
||||
int manual_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
|
||||
int vstatus_sub = orb_subscribe(ORB_ID(vehicle_status));
|
||||
int global_sp_sub = orb_subscribe(ORB_ID(vehicle_global_position_setpoint));
|
||||
int global_sp_sub = orb_subscribe(ORB_ID(position_setpoint_triplet));
|
||||
int param_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
|
||||
/* Setup of loop */
|
||||
float speed_body[3] = {0.0f, 0.0f, 0.0f};
|
||||
/* RC failsafe check */
|
||||
bool throttle_half_once = false;
|
||||
|
||||
struct pollfd fds[2] = {{ .fd = param_sub, .events = POLLIN },
|
||||
{ .fd = att_sub, .events = POLLIN }};
|
||||
|
||||
@@ -339,25 +333,10 @@ int fixedwing_control_thread_main(int argc, char *argv[])
|
||||
/* get a local copy of attitude */
|
||||
orb_copy(ORB_ID(vehicle_attitude), att_sub, &att);
|
||||
|
||||
if (global_sp_updated)
|
||||
orb_copy(ORB_ID(vehicle_global_position_setpoint), global_sp_sub, &global_sp);
|
||||
|
||||
/* currently speed in body frame is not used, but here for reference */
|
||||
if (pos_updated) {
|
||||
orb_copy(ORB_ID(vehicle_global_position), global_pos_sub, &global_pos);
|
||||
|
||||
if (att.R_valid) {
|
||||
speed_body[0] = att.R[0][0] * global_pos.vx + att.R[0][1] * global_pos.vy + att.R[0][2] * global_pos.vz;
|
||||
speed_body[1] = att.R[1][0] * global_pos.vx + att.R[1][1] * global_pos.vy + att.R[1][2] * global_pos.vz;
|
||||
speed_body[2] = att.R[2][0] * global_pos.vx + att.R[2][1] * global_pos.vy + att.R[2][2] * global_pos.vz;
|
||||
|
||||
} else {
|
||||
speed_body[0] = 0;
|
||||
speed_body[1] = 0;
|
||||
speed_body[2] = 0;
|
||||
|
||||
warnx("Did not get a valid R\n");
|
||||
}
|
||||
if (global_sp_updated) {
|
||||
struct position_setpoint_triplet_s triplet;
|
||||
orb_copy(ORB_ID(position_setpoint_triplet), global_sp_sub, &triplet);
|
||||
memcpy(&global_sp, &triplet.current, sizeof(global_sp));
|
||||
}
|
||||
|
||||
if (manual_sp_updated)
|
||||
@@ -365,106 +344,14 @@ int fixedwing_control_thread_main(int argc, char *argv[])
|
||||
orb_copy(ORB_ID(manual_control_setpoint), manual_sp_sub, &manual_sp);
|
||||
|
||||
/* check if the throttle was ever more than 50% - go later only to failsafe if yes */
|
||||
if (isfinite(manual_sp.throttle) &&
|
||||
(manual_sp.throttle >= 0.6f) &&
|
||||
(manual_sp.throttle <= 1.0f)) {
|
||||
throttle_half_once = true;
|
||||
if (isfinite(manual_sp.z) &&
|
||||
(manual_sp.z >= 0.6f) &&
|
||||
(manual_sp.z <= 1.0f)) {
|
||||
}
|
||||
|
||||
/* get the system status and the flight mode we're in */
|
||||
orb_copy(ORB_ID(vehicle_status), vstatus_sub, &vstatus);
|
||||
|
||||
/* control */
|
||||
|
||||
#warning fix this
|
||||
#if 0
|
||||
if (vstatus.navigation_state == NAVIGATION_STATE_AUTO_ ||
|
||||
vstatus.navigation_state == NAVIGATION_STATE_STABILIZED) {
|
||||
|
||||
/* simple heading control */
|
||||
control_heading(&global_pos, &global_sp, &att, &att_sp);
|
||||
|
||||
/* nail pitch and yaw (rudder) to zero. This example only controls roll (index 0) */
|
||||
actuators.control[1] = 0.0f;
|
||||
actuators.control[2] = 0.0f;
|
||||
|
||||
/* simple attitude control */
|
||||
control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* set flaps to zero */
|
||||
actuators.control[4] = 0.0f;
|
||||
|
||||
} else if (vstatus.navigation_state == NAVIGATION_STATE_MANUAL) {
|
||||
/* if in manual mode, decide between attitude stabilization (SAS) and full manual pass-through */
|
||||
} else if (vstatus.state_machine == SYSTEM_STATE_MANUAL) {
|
||||
if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_SAS) {
|
||||
|
||||
/* if the RC signal is lost, try to stay level and go slowly back down to ground */
|
||||
if (vstatus.rc_signal_lost && throttle_half_once) {
|
||||
|
||||
/* put plane into loiter */
|
||||
att_sp.roll_body = 0.3f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
|
||||
/* limit throttle to 60 % of last value if sane */
|
||||
if (isfinite(manual_sp.throttle) &&
|
||||
(manual_sp.throttle >= 0.0f) &&
|
||||
(manual_sp.throttle <= 1.0f)) {
|
||||
att_sp.thrust = 0.6f * manual_sp.throttle;
|
||||
|
||||
} else {
|
||||
att_sp.thrust = 0.0f;
|
||||
}
|
||||
|
||||
att_sp.yaw_body = 0;
|
||||
|
||||
// XXX disable yaw control, loiter
|
||||
|
||||
} else {
|
||||
|
||||
att_sp.roll_body = manual_sp.roll;
|
||||
att_sp.pitch_body = manual_sp.pitch;
|
||||
att_sp.yaw_body = 0;
|
||||
att_sp.thrust = manual_sp.throttle;
|
||||
}
|
||||
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* attitude control */
|
||||
control_attitude(&att_sp, &att, speed_body, &rates_sp, &actuators);
|
||||
|
||||
/* pass through throttle */
|
||||
actuators.control[3] = att_sp.thrust;
|
||||
|
||||
/* pass through flaps */
|
||||
if (isfinite(manual_sp.flaps)) {
|
||||
actuators.control[4] = manual_sp.flaps;
|
||||
|
||||
} else {
|
||||
actuators.control[4] = 0.0f;
|
||||
}
|
||||
|
||||
} else if (vstatus.manual_control_mode == VEHICLE_MANUAL_CONTROL_MODE_DIRECT) {
|
||||
/* directly pass through values */
|
||||
actuators.control[0] = manual_sp.roll;
|
||||
/* positive pitch means negative actuator -> pull up */
|
||||
actuators.control[1] = manual_sp.pitch;
|
||||
actuators.control[2] = manual_sp.yaw;
|
||||
actuators.control[3] = manual_sp.throttle;
|
||||
|
||||
if (isfinite(manual_sp.flaps)) {
|
||||
actuators.control[4] = manual_sp.flaps;
|
||||
|
||||
} else {
|
||||
actuators.control[4] = 0.0f;
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
/* publish rates */
|
||||
orb_publish(ORB_ID(vehicle_rates_setpoint), rates_pub, &rates_sp);
|
||||
|
||||
@@ -474,6 +361,10 @@ int fixedwing_control_thread_main(int argc, char *argv[])
|
||||
isfinite(actuators.control[2]) &&
|
||||
isfinite(actuators.control[3])) {
|
||||
orb_publish(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_pub, &actuators);
|
||||
|
||||
if (verbose) {
|
||||
warnx("published");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -308,8 +308,8 @@ int flow_position_estimator_thread_main(int argc, char *argv[])
|
||||
if (vehicle_liftoff || params.debug)
|
||||
{
|
||||
/* copy flow */
|
||||
flow_speed[0] = flow.flow_comp_x_m;
|
||||
flow_speed[1] = flow.flow_comp_y_m;
|
||||
flow_speed[0] = flow.pixel_flow_x_integral / (flow.integration_timespan / 1e6f) * flow.ground_distance_m;
|
||||
flow_speed[1] = flow.pixel_flow_y_integral / (flow.integration_timespan / 1e6f) * flow.ground_distance_m;
|
||||
flow_speed[2] = 0.0f;
|
||||
|
||||
/* convert to bodyframe velocity */
|
||||
|
||||
@@ -1,387 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file flow_speed_control.c
|
||||
*
|
||||
* Optical flow speed controller
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <stdbool.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <debug.h>
|
||||
#include <termios.h>
|
||||
#include <time.h>
|
||||
#include <math.h>
|
||||
#include <sys/prctl.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
#include <uORB/topics/vehicle_bodyframe_speed_setpoint.h>
|
||||
#include <uORB/topics/filtered_bottom_flow.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <poll.h>
|
||||
#include <mavlink/mavlink_log.h>
|
||||
|
||||
#include "flow_speed_control_params.h"
|
||||
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
static int deamon_task; /**< Handle of deamon task / thread */
|
||||
|
||||
__EXPORT int flow_speed_control_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Mainloop of position controller.
|
||||
*/
|
||||
static int flow_speed_control_thread_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_spawn_cmd().
|
||||
*/
|
||||
int flow_speed_control_main(int argc, char *argv[])
|
||||
{
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "start"))
|
||||
{
|
||||
if (thread_running)
|
||||
{
|
||||
printf("flow speed control already running\n");
|
||||
/* this is not an error */
|
||||
exit(0);
|
||||
}
|
||||
|
||||
thread_should_exit = false;
|
||||
deamon_task = task_spawn_cmd("flow_speed_control",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 6,
|
||||
4096,
|
||||
flow_speed_control_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "stop"))
|
||||
{
|
||||
thread_should_exit = true;
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "status"))
|
||||
{
|
||||
if (thread_running)
|
||||
printf("\tflow speed control app is running\n");
|
||||
else
|
||||
printf("\tflow speed control app not started\n");
|
||||
|
||||
exit(0);
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
static int
|
||||
flow_speed_control_thread_main(int argc, char *argv[])
|
||||
{
|
||||
/* welcome user */
|
||||
thread_running = true;
|
||||
static int mavlink_fd;
|
||||
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
mavlink_log_info(mavlink_fd,"[fsc] started");
|
||||
|
||||
uint32_t counter = 0;
|
||||
|
||||
/* structures */
|
||||
struct actuator_armed_s armed;
|
||||
memset(&armed, 0, sizeof(armed));
|
||||
struct vehicle_control_mode_s control_mode;
|
||||
memset(&control_mode, 0, sizeof(control_mode));
|
||||
struct filtered_bottom_flow_s filtered_flow;
|
||||
memset(&filtered_flow, 0, sizeof(filtered_flow));
|
||||
struct vehicle_bodyframe_speed_setpoint_s speed_sp;
|
||||
memset(&speed_sp, 0, sizeof(speed_sp));
|
||||
struct vehicle_attitude_setpoint_s att_sp;
|
||||
memset(&att_sp, 0, sizeof(att_sp));
|
||||
|
||||
/* subscribe to attitude, motor setpoints and system state */
|
||||
int parameter_update_sub = orb_subscribe(ORB_ID(parameter_update));
|
||||
int vehicle_attitude_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
int armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||
int control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
|
||||
int filtered_bottom_flow_sub = orb_subscribe(ORB_ID(filtered_bottom_flow));
|
||||
int vehicle_bodyframe_speed_setpoint_sub = orb_subscribe(ORB_ID(vehicle_bodyframe_speed_setpoint));
|
||||
|
||||
orb_advert_t att_sp_pub;
|
||||
bool attitude_setpoint_adverted = false;
|
||||
|
||||
/* parameters init*/
|
||||
struct flow_speed_control_params params;
|
||||
struct flow_speed_control_param_handles param_handles;
|
||||
parameters_init(¶m_handles);
|
||||
parameters_update(¶m_handles, ¶ms);
|
||||
|
||||
/* register the perf counter */
|
||||
perf_counter_t mc_loop_perf = perf_alloc(PC_ELAPSED, "flow_speed_control_runtime");
|
||||
perf_counter_t mc_interval_perf = perf_alloc(PC_INTERVAL, "flow_speed_control_interval");
|
||||
perf_counter_t mc_err_perf = perf_alloc(PC_COUNT, "flow_speed_control_err");
|
||||
|
||||
static bool sensors_ready = false;
|
||||
static bool status_changed = false;
|
||||
|
||||
while (!thread_should_exit)
|
||||
{
|
||||
/* wait for first attitude msg to be sure all data are available */
|
||||
if (sensors_ready)
|
||||
{
|
||||
/* polling */
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = vehicle_bodyframe_speed_setpoint_sub, .events = POLLIN }, // speed setpoint from pos controller
|
||||
{ .fd = parameter_update_sub, .events = POLLIN }
|
||||
};
|
||||
|
||||
/* wait for a position update, check for exit condition every 5000 ms */
|
||||
int ret = poll(fds, 2, 500);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
/* poll error, count it in perf */
|
||||
perf_count(mc_err_perf);
|
||||
}
|
||||
else if (ret == 0)
|
||||
{
|
||||
/* no return value, ignore */
|
||||
// printf("[flow speed control] no bodyframe speed setpoints updates\n");
|
||||
}
|
||||
else
|
||||
{
|
||||
/* parameter update available? */
|
||||
if (fds[1].revents & POLLIN)
|
||||
{
|
||||
/* read from param to clear updated flag */
|
||||
struct parameter_update_s update;
|
||||
orb_copy(ORB_ID(parameter_update), parameter_update_sub, &update);
|
||||
|
||||
parameters_update(¶m_handles, ¶ms);
|
||||
mavlink_log_info(mavlink_fd,"[fsp] parameters updated.");
|
||||
}
|
||||
|
||||
/* only run controller if position/speed changed */
|
||||
if (fds[0].revents & POLLIN)
|
||||
{
|
||||
perf_begin(mc_loop_perf);
|
||||
|
||||
/* get a local copy of the armed topic */
|
||||
orb_copy(ORB_ID(actuator_armed), armed_sub, &armed);
|
||||
/* get a local copy of the control mode */
|
||||
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
|
||||
/* get a local copy of filtered bottom flow */
|
||||
orb_copy(ORB_ID(filtered_bottom_flow), filtered_bottom_flow_sub, &filtered_flow);
|
||||
/* get a local copy of bodyframe speed setpoint */
|
||||
orb_copy(ORB_ID(vehicle_bodyframe_speed_setpoint), vehicle_bodyframe_speed_setpoint_sub, &speed_sp);
|
||||
/* get a local copy of control mode */
|
||||
orb_copy(ORB_ID(vehicle_control_mode), control_mode_sub, &control_mode);
|
||||
|
||||
if (control_mode.flag_control_velocity_enabled)
|
||||
{
|
||||
/* calc new roll/pitch */
|
||||
float pitch_body = -(speed_sp.vx - filtered_flow.vx) * params.speed_p;
|
||||
float roll_body = (speed_sp.vy - filtered_flow.vy) * params.speed_p;
|
||||
|
||||
if(status_changed == false)
|
||||
mavlink_log_info(mavlink_fd,"[fsc] flow SPEED control engaged");
|
||||
|
||||
status_changed = true;
|
||||
|
||||
/* limit roll and pitch corrections */
|
||||
if((pitch_body <= params.limit_pitch) && (pitch_body >= -params.limit_pitch))
|
||||
{
|
||||
att_sp.pitch_body = pitch_body;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(pitch_body > params.limit_pitch)
|
||||
att_sp.pitch_body = params.limit_pitch;
|
||||
if(pitch_body < -params.limit_pitch)
|
||||
att_sp.pitch_body = -params.limit_pitch;
|
||||
}
|
||||
|
||||
if((roll_body <= params.limit_roll) && (roll_body >= -params.limit_roll))
|
||||
{
|
||||
att_sp.roll_body = roll_body;
|
||||
}
|
||||
else
|
||||
{
|
||||
if(roll_body > params.limit_roll)
|
||||
att_sp.roll_body = params.limit_roll;
|
||||
if(roll_body < -params.limit_roll)
|
||||
att_sp.roll_body = -params.limit_roll;
|
||||
}
|
||||
|
||||
/* set yaw setpoint forward*/
|
||||
att_sp.yaw_body = speed_sp.yaw_sp;
|
||||
|
||||
/* add trim from parameters */
|
||||
att_sp.roll_body = att_sp.roll_body + params.trim_roll;
|
||||
att_sp.pitch_body = att_sp.pitch_body + params.trim_pitch;
|
||||
|
||||
att_sp.thrust = speed_sp.thrust_sp;
|
||||
att_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
/* publish new attitude setpoint */
|
||||
if(isfinite(att_sp.pitch_body) && isfinite(att_sp.roll_body) && isfinite(att_sp.yaw_body) && isfinite(att_sp.thrust))
|
||||
{
|
||||
if (attitude_setpoint_adverted)
|
||||
{
|
||||
orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp);
|
||||
}
|
||||
else
|
||||
{
|
||||
att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp);
|
||||
attitude_setpoint_adverted = true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
warnx("NaN in flow speed controller!");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if(status_changed == true)
|
||||
mavlink_log_info(mavlink_fd,"[fsc] flow SPEED controller disengaged.");
|
||||
|
||||
status_changed = false;
|
||||
|
||||
/* reset attitude setpoint */
|
||||
att_sp.roll_body = 0.0f;
|
||||
att_sp.pitch_body = 0.0f;
|
||||
att_sp.thrust = 0.0f;
|
||||
att_sp.yaw_body = 0.0f;
|
||||
}
|
||||
|
||||
/* measure in what intervals the controller runs */
|
||||
perf_count(mc_interval_perf);
|
||||
perf_end(mc_loop_perf);
|
||||
}
|
||||
}
|
||||
|
||||
counter++;
|
||||
}
|
||||
else
|
||||
{
|
||||
/* sensors not ready waiting for first attitude msg */
|
||||
|
||||
/* polling */
|
||||
struct pollfd fds[1] = {
|
||||
{ .fd = vehicle_attitude_sub, .events = POLLIN },
|
||||
};
|
||||
|
||||
/* wait for a flow msg, check for exit condition every 5 s */
|
||||
int ret = poll(fds, 1, 5000);
|
||||
|
||||
if (ret < 0)
|
||||
{
|
||||
/* poll error, count it in perf */
|
||||
perf_count(mc_err_perf);
|
||||
}
|
||||
else if (ret == 0)
|
||||
{
|
||||
/* no return value, ignore */
|
||||
mavlink_log_info(mavlink_fd,"[fsc] no attitude received.");
|
||||
}
|
||||
else
|
||||
{
|
||||
if (fds[0].revents & POLLIN)
|
||||
{
|
||||
sensors_ready = true;
|
||||
mavlink_log_info(mavlink_fd,"[fsp] initialized.");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
mavlink_log_info(mavlink_fd,"[fsc] ending now...");
|
||||
|
||||
thread_running = false;
|
||||
|
||||
close(parameter_update_sub);
|
||||
close(vehicle_attitude_sub);
|
||||
close(vehicle_bodyframe_speed_setpoint_sub);
|
||||
close(filtered_bottom_flow_sub);
|
||||
close(armed_sub);
|
||||
close(control_mode_sub);
|
||||
close(att_sp_pub);
|
||||
|
||||
perf_print_counter(mc_loop_perf);
|
||||
perf_free(mc_loop_perf);
|
||||
|
||||
fflush(stdout);
|
||||
return 0;
|
||||
}
|
||||
@@ -1,70 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file flow_speed_control_params.c
|
||||
*
|
||||
*/
|
||||
|
||||
#include "flow_speed_control_params.h"
|
||||
|
||||
/* controller parameters */
|
||||
PARAM_DEFINE_FLOAT(FSC_S_P, 0.1f);
|
||||
PARAM_DEFINE_FLOAT(FSC_L_PITCH, 0.4f);
|
||||
PARAM_DEFINE_FLOAT(FSC_L_ROLL, 0.4f);
|
||||
|
||||
int parameters_init(struct flow_speed_control_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
h->speed_p = param_find("FSC_S_P");
|
||||
h->limit_pitch = param_find("FSC_L_PITCH");
|
||||
h->limit_roll = param_find("FSC_L_ROLL");
|
||||
h->trim_roll = param_find("TRIM_ROLL");
|
||||
h->trim_pitch = param_find("TRIM_PITCH");
|
||||
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int parameters_update(const struct flow_speed_control_param_handles *h, struct flow_speed_control_params *p)
|
||||
{
|
||||
param_get(h->speed_p, &(p->speed_p));
|
||||
param_get(h->limit_pitch, &(p->limit_pitch));
|
||||
param_get(h->limit_roll, &(p->limit_roll));
|
||||
param_get(h->trim_roll, &(p->trim_roll));
|
||||
param_get(h->trim_pitch, &(p->trim_pitch));
|
||||
|
||||
return OK;
|
||||
}
|
||||
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (c) 2013, 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
|
||||
@@ -34,7 +33,8 @@
|
||||
/**
|
||||
* @file hwtest.c
|
||||
*
|
||||
* Simple functional hardware test.
|
||||
* Simple output test.
|
||||
* @ref Documentation https://pixhawk.org/dev/examples/write_output
|
||||
*
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
*/
|
||||
@@ -45,30 +45,80 @@
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/actuator_controls.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
|
||||
__EXPORT int ex_hwtest_main(int argc, char *argv[]);
|
||||
|
||||
int ex_hwtest_main(int argc, char *argv[])
|
||||
{
|
||||
struct actuator_controls_s actuators;
|
||||
memset(&actuators, 0, sizeof(actuators));
|
||||
orb_advert_t actuator_pub_fd = orb_advertise(ORB_ID(actuator_controls_0), &actuators);
|
||||
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");
|
||||
|
||||
int i;
|
||||
float rcvalue = -1.0f;
|
||||
hrt_abstime stime;
|
||||
struct actuator_controls_s actuators;
|
||||
memset(&actuators, 0, sizeof(actuators));
|
||||
orb_advert_t actuator_pub_fd = orb_advertise(ORB_ID(actuator_controls_0), &actuators);
|
||||
|
||||
while (true) {
|
||||
stime = hrt_absolute_time();
|
||||
while (hrt_absolute_time() - stime < 1000000) {
|
||||
for (i=0; i<8; i++)
|
||||
actuators.control[i] = rcvalue;
|
||||
actuators.timestamp = hrt_absolute_time();
|
||||
orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators);
|
||||
}
|
||||
warnx("servos set to %.1f", rcvalue);
|
||||
rcvalue *= -1.0f;
|
||||
}
|
||||
struct actuator_armed_s arm;
|
||||
memset(&arm, 0 , sizeof(arm));
|
||||
|
||||
return OK;
|
||||
arm.timestamp = hrt_absolute_time();
|
||||
arm.ready_to_arm = true;
|
||||
arm.armed = true;
|
||||
orb_advert_t arm_pub_fd = orb_advertise(ORB_ID(actuator_armed), &arm);
|
||||
orb_publish(ORB_ID(actuator_armed), arm_pub_fd, &arm);
|
||||
|
||||
/* read back values to validate */
|
||||
int arm_sub_fd = orb_subscribe(ORB_ID(actuator_armed));
|
||||
orb_copy(ORB_ID(actuator_armed), arm_sub_fd, &arm);
|
||||
|
||||
if (arm.ready_to_arm && arm.armed) {
|
||||
warnx("Actuator armed");
|
||||
|
||||
} else {
|
||||
errx(1, "Arming actuators failed");
|
||||
}
|
||||
|
||||
hrt_abstime stime;
|
||||
|
||||
int count = 0;
|
||||
|
||||
while (count != 36) {
|
||||
stime = hrt_absolute_time();
|
||||
|
||||
while (hrt_absolute_time() - stime < 1000000) {
|
||||
for (int i = 0; i != 2; i++) {
|
||||
if (count <= 5) {
|
||||
actuators.control[i] = -1.0f;
|
||||
|
||||
} else if (count <= 10) {
|
||||
actuators.control[i] = -0.7f;
|
||||
|
||||
} else if (count <= 15) {
|
||||
actuators.control[i] = -0.5f;
|
||||
|
||||
} else if (count <= 20) {
|
||||
actuators.control[i] = -0.3f;
|
||||
|
||||
} else if (count <= 25) {
|
||||
actuators.control[i] = 0.0f;
|
||||
|
||||
} else if (count <= 30) {
|
||||
actuators.control[i] = 0.3f;
|
||||
|
||||
} else {
|
||||
actuators.control[i] = 0.5f;
|
||||
}
|
||||
}
|
||||
|
||||
actuators.timestamp = hrt_absolute_time();
|
||||
orb_publish(ORB_ID(actuator_controls_0), actuator_pub_fd, &actuators);
|
||||
usleep(10000);
|
||||
}
|
||||
|
||||
warnx("count %i", count);
|
||||
count++;
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -0,0 +1,298 @@
|
||||
function [xa_apo,Pa_apo,Rot_matrix,eulerAngles,debugOutput]...
|
||||
= AttitudeEKF(approx_prediction,use_inertia_matrix,zFlag,dt,z,q_rotSpeed,q_rotAcc,q_acc,q_mag,r_gyro,r_accel,r_mag,J)
|
||||
|
||||
|
||||
%LQG Postion Estimator and Controller
|
||||
% Observer:
|
||||
% x[n|n] = x[n|n-1] + M(y[n] - Cx[n|n-1] - Du[n])
|
||||
% x[n+1|n] = Ax[n|n] + Bu[n]
|
||||
%
|
||||
% $Author: Tobias Naegeli $ $Date: 2014 $ $Revision: 3 $
|
||||
%
|
||||
%
|
||||
% Arguments:
|
||||
% approx_prediction: if 1 then the exponential map is approximated with a
|
||||
% first order taylor approximation. has at the moment not a big influence
|
||||
% (just 1st or 2nd order approximation) we should change it to rodriquez
|
||||
% approximation.
|
||||
% use_inertia_matrix: set to true if you have the inertia matrix J for your
|
||||
% quadrotor
|
||||
% xa_apo_k: old state vectotr
|
||||
% zFlag: if sensor measurement is available [gyro, acc, mag]
|
||||
% dt: dt in s
|
||||
% z: measurements [gyro, acc, mag]
|
||||
% q_rotSpeed: process noise gyro
|
||||
% q_rotAcc: process noise gyro acceleration
|
||||
% q_acc: process noise acceleration
|
||||
% q_mag: process noise magnetometer
|
||||
% r_gyro: measurement noise gyro
|
||||
% r_accel: measurement noise accel
|
||||
% r_mag: measurement noise mag
|
||||
% J: moment of inertia matrix
|
||||
|
||||
|
||||
% Output:
|
||||
% xa_apo: updated state vectotr
|
||||
% Pa_apo: updated state covariance matrix
|
||||
% Rot_matrix: rotation matrix
|
||||
% eulerAngles: euler angles
|
||||
% debugOutput: not used
|
||||
|
||||
|
||||
%% model specific parameters
|
||||
|
||||
|
||||
|
||||
% compute once the inverse of the Inertia
|
||||
persistent Ji;
|
||||
if isempty(Ji)
|
||||
Ji=single(inv(J));
|
||||
end
|
||||
|
||||
%% init
|
||||
persistent x_apo
|
||||
if(isempty(x_apo))
|
||||
gyro_init=single([0;0;0]);
|
||||
gyro_acc_init=single([0;0;0]);
|
||||
acc_init=single([0;0;-9.81]);
|
||||
mag_init=single([1;0;0]);
|
||||
x_apo=single([gyro_init;gyro_acc_init;acc_init;mag_init]);
|
||||
|
||||
end
|
||||
|
||||
persistent P_apo
|
||||
if(isempty(P_apo))
|
||||
% P_apo = single(eye(NSTATES) * 1000);
|
||||
P_apo = single(200*ones(12));
|
||||
end
|
||||
|
||||
debugOutput = single(zeros(4,1));
|
||||
|
||||
%% copy the states
|
||||
wx= x_apo(1); % x body angular rate
|
||||
wy= x_apo(2); % y body angular rate
|
||||
wz= x_apo(3); % z body angular rate
|
||||
|
||||
wax= x_apo(4); % x body angular acceleration
|
||||
way= x_apo(5); % y body angular acceleration
|
||||
waz= x_apo(6); % z body angular acceleration
|
||||
|
||||
zex= x_apo(7); % x component gravity vector
|
||||
zey= x_apo(8); % y component gravity vector
|
||||
zez= x_apo(9); % z component gravity vector
|
||||
|
||||
mux= x_apo(10); % x component magnetic field vector
|
||||
muy= x_apo(11); % y component magnetic field vector
|
||||
muz= x_apo(12); % z component magnetic field vector
|
||||
|
||||
|
||||
|
||||
|
||||
%% prediction section
|
||||
% compute the apriori state estimate from the previous aposteriori estimate
|
||||
%body angular accelerations
|
||||
if (use_inertia_matrix==1)
|
||||
wak =[wax;way;waz]+Ji*(-cross([wax;way;waz],J*[wax;way;waz]))*dt;
|
||||
else
|
||||
wak =[wax;way;waz];
|
||||
end
|
||||
|
||||
%body angular rates
|
||||
wk =[wx; wy; wz] + dt*wak;
|
||||
|
||||
%derivative of the prediction rotation matrix
|
||||
O=[0,-wz,wy;wz,0,-wx;-wy,wx,0]';
|
||||
|
||||
%prediction of the earth z vector
|
||||
if (approx_prediction==1)
|
||||
%e^(Odt)=I+dt*O+dt^2/2!O^2
|
||||
% so we do a first order approximation of the exponential map
|
||||
zek =(O*dt+single(eye(3)))*[zex;zey;zez];
|
||||
|
||||
else
|
||||
zek =(single(eye(3))+O*dt+dt^2/2*O^2)*[zex;zey;zez];
|
||||
%zek =expm2(O*dt)*[zex;zey;zez]; not working because use double
|
||||
%precision
|
||||
end
|
||||
|
||||
|
||||
|
||||
%prediction of the magnetic vector
|
||||
if (approx_prediction==1)
|
||||
%e^(Odt)=I+dt*O+dt^2/2!O^2
|
||||
% so we do a first order approximation of the exponential map
|
||||
muk =(O*dt+single(eye(3)))*[mux;muy;muz];
|
||||
else
|
||||
muk =(single(eye(3))+O*dt+dt^2/2*O^2)*[mux;muy;muz];
|
||||
%muk =expm2(O*dt)*[mux;muy;muz]; not working because use double
|
||||
%precision
|
||||
end
|
||||
|
||||
x_apr=[wk;wak;zek;muk];
|
||||
|
||||
% compute the apriori error covariance estimate from the previous
|
||||
%aposteriori estimate
|
||||
|
||||
EZ=[0,zez,-zey;
|
||||
-zez,0,zex;
|
||||
zey,-zex,0]';
|
||||
MA=[0,muz,-muy;
|
||||
-muz,0,mux;
|
||||
muy,-mux,0]';
|
||||
|
||||
E=single(eye(3));
|
||||
Z=single(zeros(3));
|
||||
|
||||
A_lin=[ Z, E, Z, Z
|
||||
Z, Z, Z, Z
|
||||
EZ, Z, O, Z
|
||||
MA, Z, Z, O];
|
||||
|
||||
A_lin=eye(12)+A_lin*dt;
|
||||
|
||||
%process covariance matrix
|
||||
|
||||
persistent Q
|
||||
if (isempty(Q))
|
||||
Q=diag([ q_rotSpeed,q_rotSpeed,q_rotSpeed,...
|
||||
q_rotAcc,q_rotAcc,q_rotAcc,...
|
||||
q_acc,q_acc,q_acc,...
|
||||
q_mag,q_mag,q_mag]);
|
||||
end
|
||||
|
||||
P_apr=A_lin*P_apo*A_lin'+Q;
|
||||
|
||||
|
||||
%% update
|
||||
if zFlag(1)==1&&zFlag(2)==1&&zFlag(3)==1
|
||||
|
||||
% R=[r_gyro,0,0,0,0,0,0,0,0;
|
||||
% 0,r_gyro,0,0,0,0,0,0,0;
|
||||
% 0,0,r_gyro,0,0,0,0,0,0;
|
||||
% 0,0,0,r_accel,0,0,0,0,0;
|
||||
% 0,0,0,0,r_accel,0,0,0,0;
|
||||
% 0,0,0,0,0,r_accel,0,0,0;
|
||||
% 0,0,0,0,0,0,r_mag,0,0;
|
||||
% 0,0,0,0,0,0,0,r_mag,0;
|
||||
% 0,0,0,0,0,0,0,0,r_mag];
|
||||
R_v=[r_gyro,r_gyro,r_gyro,r_accel,r_accel,r_accel,r_mag,r_mag,r_mag];
|
||||
%observation matrix
|
||||
%[zw;ze;zmk];
|
||||
H_k=[ E, Z, Z, Z;
|
||||
Z, Z, E, Z;
|
||||
Z, Z, Z, E];
|
||||
|
||||
y_k=z(1:9)-H_k*x_apr;
|
||||
|
||||
|
||||
%S_k=H_k*P_apr*H_k'+R;
|
||||
S_k=H_k*P_apr*H_k';
|
||||
S_k(1:9+1:end) = S_k(1:9+1:end) + R_v;
|
||||
K_k=(P_apr*H_k'/(S_k));
|
||||
|
||||
|
||||
x_apo=x_apr+K_k*y_k;
|
||||
P_apo=(eye(12)-K_k*H_k)*P_apr;
|
||||
else
|
||||
if zFlag(1)==1&&zFlag(2)==0&&zFlag(3)==0
|
||||
|
||||
R=[r_gyro,0,0;
|
||||
0,r_gyro,0;
|
||||
0,0,r_gyro];
|
||||
R_v=[r_gyro,r_gyro,r_gyro];
|
||||
%observation matrix
|
||||
|
||||
H_k=[ E, Z, Z, Z];
|
||||
|
||||
y_k=z(1:3)-H_k(1:3,1:12)*x_apr;
|
||||
|
||||
% S_k=H_k(1:3,1:12)*P_apr*H_k(1:3,1:12)'+R(1:3,1:3);
|
||||
S_k=H_k(1:3,1:12)*P_apr*H_k(1:3,1:12)';
|
||||
S_k(1:3+1:end) = S_k(1:3+1:end) + R_v;
|
||||
K_k=(P_apr*H_k(1:3,1:12)'/(S_k));
|
||||
|
||||
|
||||
x_apo=x_apr+K_k*y_k;
|
||||
P_apo=(eye(12)-K_k*H_k(1:3,1:12))*P_apr;
|
||||
else
|
||||
if zFlag(1)==1&&zFlag(2)==1&&zFlag(3)==0
|
||||
|
||||
% R=[r_gyro,0,0,0,0,0;
|
||||
% 0,r_gyro,0,0,0,0;
|
||||
% 0,0,r_gyro,0,0,0;
|
||||
% 0,0,0,r_accel,0,0;
|
||||
% 0,0,0,0,r_accel,0;
|
||||
% 0,0,0,0,0,r_accel];
|
||||
|
||||
R_v=[r_gyro,r_gyro,r_gyro,r_accel,r_accel,r_accel];
|
||||
%observation matrix
|
||||
|
||||
H_k=[ E, Z, Z, Z;
|
||||
Z, Z, E, Z];
|
||||
|
||||
y_k=z(1:6)-H_k(1:6,1:12)*x_apr;
|
||||
|
||||
% S_k=H_k(1:6,1:12)*P_apr*H_k(1:6,1:12)'+R(1:6,1:6);
|
||||
S_k=H_k(1:6,1:12)*P_apr*H_k(1:6,1:12)';
|
||||
S_k(1:6+1:end) = S_k(1:6+1:end) + R_v;
|
||||
K_k=(P_apr*H_k(1:6,1:12)'/(S_k));
|
||||
|
||||
|
||||
x_apo=x_apr+K_k*y_k;
|
||||
P_apo=(eye(12)-K_k*H_k(1:6,1:12))*P_apr;
|
||||
else
|
||||
if zFlag(1)==1&&zFlag(2)==0&&zFlag(3)==1
|
||||
% R=[r_gyro,0,0,0,0,0;
|
||||
% 0,r_gyro,0,0,0,0;
|
||||
% 0,0,r_gyro,0,0,0;
|
||||
% 0,0,0,r_mag,0,0;
|
||||
% 0,0,0,0,r_mag,0;
|
||||
% 0,0,0,0,0,r_mag];
|
||||
R_v=[r_gyro,r_gyro,r_gyro,r_mag,r_mag,r_mag];
|
||||
%observation matrix
|
||||
|
||||
H_k=[ E, Z, Z, Z;
|
||||
Z, Z, Z, E];
|
||||
|
||||
y_k=[z(1:3);z(7:9)]-H_k(1:6,1:12)*x_apr;
|
||||
|
||||
%S_k=H_k(1:6,1:12)*P_apr*H_k(1:6,1:12)'+R(1:6,1:6);
|
||||
S_k=H_k(1:6,1:12)*P_apr*H_k(1:6,1:12)';
|
||||
S_k(1:6+1:end) = S_k(1:6+1:end) + R_v;
|
||||
K_k=(P_apr*H_k(1:6,1:12)'/(S_k));
|
||||
|
||||
|
||||
x_apo=x_apr+K_k*y_k;
|
||||
P_apo=(eye(12)-K_k*H_k(1:6,1:12))*P_apr;
|
||||
else
|
||||
x_apo=x_apr;
|
||||
P_apo=P_apr;
|
||||
end
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
|
||||
|
||||
%% euler anglels extraction
|
||||
z_n_b = -x_apo(7:9)./norm(x_apo(7:9));
|
||||
m_n_b = x_apo(10:12)./norm(x_apo(10:12));
|
||||
|
||||
y_n_b=cross(z_n_b,m_n_b);
|
||||
y_n_b=y_n_b./norm(y_n_b);
|
||||
|
||||
x_n_b=(cross(y_n_b,z_n_b));
|
||||
x_n_b=x_n_b./norm(x_n_b);
|
||||
|
||||
|
||||
xa_apo=x_apo;
|
||||
Pa_apo=P_apo;
|
||||
% rotation matrix from earth to body system
|
||||
Rot_matrix=[x_n_b,y_n_b,z_n_b];
|
||||
|
||||
|
||||
phi=atan2(Rot_matrix(2,3),Rot_matrix(3,3));
|
||||
theta=-asin(Rot_matrix(1,3));
|
||||
psi=atan2(Rot_matrix(1,2),Rot_matrix(1,1));
|
||||
eulerAngles=[phi;theta;psi];
|
||||
|
||||
@@ -0,0 +1,502 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<deployment-project plugin="plugin.matlabcoder" plugin-version="R2013a">
|
||||
<configuration target="target.matlab.coder" target-name="MEX, C, and C++ Code Generation" name="attitudeKalmanfilter" location="/home/thomasgubler/src/Firmware/src/modules/attitude_estimator_ekf" file="/home/thomasgubler/src/Firmware/src/modules/attitude_estimator_ekf/attitudeKalmanfilter.prj" build-checksum="1213478164">
|
||||
<profile key="profile.mex">
|
||||
<param.MergeInstrumentationResults>false</param.MergeInstrumentationResults>
|
||||
<param.BuiltInstrumentedMex>false</param.BuiltInstrumentedMex>
|
||||
<param.RanInstrumentedMex>false</param.RanInstrumentedMex>
|
||||
<param.WorkingFolder>option.WorkingFolder.Project</param.WorkingFolder>
|
||||
<param.SpecifiedWorkingFolder />
|
||||
<param.BuildFolder>option.BuildFolder.Project</param.BuildFolder>
|
||||
<param.SpecifiedBuildFolder />
|
||||
<param.SearchPaths />
|
||||
<param.ResponsivenessChecks>true</param.ResponsivenessChecks>
|
||||
<param.ExtrinsicCalls>true</param.ExtrinsicCalls>
|
||||
<param.IntegrityChecks>true</param.IntegrityChecks>
|
||||
<param.SaturateOnIntegerOverflow>true</param.SaturateOnIntegerOverflow>
|
||||
<param.GlobalDataSyncMethod>option.GlobalDataSyncMethod.SyncAlways</param.GlobalDataSyncMethod>
|
||||
<param.EnableVariableSizing>true</param.EnableVariableSizing>
|
||||
<param.DynamicMemoryAllocation>option.DynamicMemoryAllocation.Threshold</param.DynamicMemoryAllocation>
|
||||
<param.DynamicMemoryAllocationThreshold>65536</param.DynamicMemoryAllocationThreshold>
|
||||
<param.StackUsageMax>200000</param.StackUsageMax>
|
||||
<param.FilePartitionMethod>option.FilePartitionMethod.MapMFileToCFile</param.FilePartitionMethod>
|
||||
<param.GenerateComments>true</param.GenerateComments>
|
||||
<param.MATLABSourceComments>false</param.MATLABSourceComments>
|
||||
<param.ReservedNameArray />
|
||||
<param.EnableScreener>true</param.EnableScreener>
|
||||
<param.EnableDebugging>false</param.EnableDebugging>
|
||||
<param.GenerateReport>true</param.GenerateReport>
|
||||
<param.LaunchReport>false</param.LaunchReport>
|
||||
<param.CustomSourceCode />
|
||||
<param.CustomHeaderCode />
|
||||
<param.CustomInitializer />
|
||||
<param.CustomTerminator />
|
||||
<param.CustomInclude />
|
||||
<param.CustomSource />
|
||||
<param.CustomLibrary />
|
||||
<param.PostCodeGenCommand />
|
||||
<param.ProposeFixedPointDataTypes>true</param.ProposeFixedPointDataTypes>
|
||||
<param.mex.GenCodeOnly>false</param.mex.GenCodeOnly>
|
||||
<param.ConstantFoldingTimeout>40000</param.ConstantFoldingTimeout>
|
||||
<param.RecursionLimit>100</param.RecursionLimit>
|
||||
<param.TargetLang>option.TargetLang.C</param.TargetLang>
|
||||
<param.EchoExpressions>true</param.EchoExpressions>
|
||||
<param.InlineThreshold>10</param.InlineThreshold>
|
||||
<param.InlineThresholdMax>200</param.InlineThresholdMax>
|
||||
<param.InlineStackLimit>4000</param.InlineStackLimit>
|
||||
<param.EnableMemcpy>true</param.EnableMemcpy>
|
||||
<param.MemcpyThreshold>64</param.MemcpyThreshold>
|
||||
<param.EnableOpenMP>true</param.EnableOpenMP>
|
||||
<param.InitFltsAndDblsToZero>true</param.InitFltsAndDblsToZero>
|
||||
<param.ConstantInputs>option.ConstantInputs.CheckValues</param.ConstantInputs>
|
||||
<unset>
|
||||
<param.MergeInstrumentationResults />
|
||||
<param.BuiltInstrumentedMex />
|
||||
<param.RanInstrumentedMex />
|
||||
<param.WorkingFolder />
|
||||
<param.SpecifiedWorkingFolder />
|
||||
<param.BuildFolder />
|
||||
<param.SpecifiedBuildFolder />
|
||||
<param.SearchPaths />
|
||||
<param.ResponsivenessChecks />
|
||||
<param.ExtrinsicCalls />
|
||||
<param.IntegrityChecks />
|
||||
<param.SaturateOnIntegerOverflow />
|
||||
<param.GlobalDataSyncMethod />
|
||||
<param.EnableVariableSizing />
|
||||
<param.DynamicMemoryAllocation />
|
||||
<param.DynamicMemoryAllocationThreshold />
|
||||
<param.StackUsageMax />
|
||||
<param.FilePartitionMethod />
|
||||
<param.GenerateComments />
|
||||
<param.MATLABSourceComments />
|
||||
<param.ReservedNameArray />
|
||||
<param.EnableScreener />
|
||||
<param.EnableDebugging />
|
||||
<param.GenerateReport />
|
||||
<param.LaunchReport />
|
||||
<param.CustomSourceCode />
|
||||
<param.CustomHeaderCode />
|
||||
<param.CustomInitializer />
|
||||
<param.CustomTerminator />
|
||||
<param.CustomInclude />
|
||||
<param.CustomSource />
|
||||
<param.CustomLibrary />
|
||||
<param.PostCodeGenCommand />
|
||||
<param.ProposeFixedPointDataTypes />
|
||||
<param.mex.GenCodeOnly />
|
||||
<param.ConstantFoldingTimeout />
|
||||
<param.RecursionLimit />
|
||||
<param.TargetLang />
|
||||
<param.EchoExpressions />
|
||||
<param.InlineThreshold />
|
||||
<param.InlineThresholdMax />
|
||||
<param.InlineStackLimit />
|
||||
<param.EnableMemcpy />
|
||||
<param.MemcpyThreshold />
|
||||
<param.EnableOpenMP />
|
||||
<param.InitFltsAndDblsToZero />
|
||||
<param.ConstantInputs />
|
||||
</unset>
|
||||
</profile>
|
||||
<profile key="profile.c">
|
||||
<param.grt.GenCodeOnly>true</param.grt.GenCodeOnly>
|
||||
<param.WorkingFolder>option.WorkingFolder.Project</param.WorkingFolder>
|
||||
<param.SpecifiedWorkingFolder />
|
||||
<param.BuildFolder>option.BuildFolder.Specified</param.BuildFolder>
|
||||
<param.SpecifiedBuildFolder>codegen</param.SpecifiedBuildFolder>
|
||||
<param.SearchPaths />
|
||||
<param.SaturateOnIntegerOverflow>true</param.SaturateOnIntegerOverflow>
|
||||
<param.PurelyIntegerCode>false</param.PurelyIntegerCode>
|
||||
<param.SupportNonFinite>false</param.SupportNonFinite>
|
||||
<param.EnableVariableSizing>false</param.EnableVariableSizing>
|
||||
<param.DynamicMemoryAllocation>option.DynamicMemoryAllocation.Threshold</param.DynamicMemoryAllocation>
|
||||
<param.DynamicMemoryAllocationThreshold>65536</param.DynamicMemoryAllocationThreshold>
|
||||
<param.StackUsageMax>4000</param.StackUsageMax>
|
||||
<param.MultiInstanceCode>false</param.MultiInstanceCode>
|
||||
<param.FilePartitionMethod>option.FilePartitionMethod.SingleFile</param.FilePartitionMethod>
|
||||
<param.GenerateComments>true</param.GenerateComments>
|
||||
<param.MATLABSourceComments>true</param.MATLABSourceComments>
|
||||
<param.MATLABFcnDesc>false</param.MATLABFcnDesc>
|
||||
<param.DataTypeReplacement>option.DataTypeReplacement.CBuiltIn</param.DataTypeReplacement>
|
||||
<param.ConvertIfToSwitch>false</param.ConvertIfToSwitch>
|
||||
<param.PreserveExternInFcnDecls>true</param.PreserveExternInFcnDecls>
|
||||
<param.ParenthesesLevel>option.ParenthesesLevel.Nominal</param.ParenthesesLevel>
|
||||
<param.MaxIdLength>31</param.MaxIdLength>
|
||||
<param.CustomSymbolStrGlobalVar>$M$N</param.CustomSymbolStrGlobalVar>
|
||||
<param.CustomSymbolStrType>$M$N</param.CustomSymbolStrType>
|
||||
<param.CustomSymbolStrField>$M$N</param.CustomSymbolStrField>
|
||||
<param.CustomSymbolStrFcn>$M$N</param.CustomSymbolStrFcn>
|
||||
<param.CustomSymbolStrTmpVar>$M$N</param.CustomSymbolStrTmpVar>
|
||||
<param.CustomSymbolStrMacro>$M$N</param.CustomSymbolStrMacro>
|
||||
<param.CustomSymbolStrEMXArray>emxArray_$M$N</param.CustomSymbolStrEMXArray>
|
||||
<param.CustomSymbolStrEMXArrayFcn>emx$M$N</param.CustomSymbolStrEMXArrayFcn>
|
||||
<param.ReservedNameArray />
|
||||
<param.EnableScreener>true</param.EnableScreener>
|
||||
<param.Verbose>false</param.Verbose>
|
||||
<param.GenerateReport>true</param.GenerateReport>
|
||||
<param.GenerateCodeMetricsReport>true</param.GenerateCodeMetricsReport>
|
||||
<param.GenerateCodeReplacementReport>false</param.GenerateCodeReplacementReport>
|
||||
<param.LaunchReport>true</param.LaunchReport>
|
||||
<param.CustomSourceCode />
|
||||
<param.CustomHeaderCode />
|
||||
<param.CustomInitializer />
|
||||
<param.CustomTerminator />
|
||||
<param.CustomInclude />
|
||||
<param.CustomSource />
|
||||
<param.CustomLibrary />
|
||||
<param.PostCodeGenCommand />
|
||||
<param.CodeReplacementLibrary>C89/C90 (ANSI)</param.CodeReplacementLibrary>
|
||||
<param.SameHardware>true</param.SameHardware>
|
||||
<param.HardwareVendor.Production>ARM Compatible</param.HardwareVendor.Production>
|
||||
<param.HardwareType.Production>ARM Cortex</param.HardwareType.Production>
|
||||
<var.instance.enabled.Production>true</var.instance.enabled.Production>
|
||||
<param.HardwareSizeChar.Production>8</param.HardwareSizeChar.Production>
|
||||
<param.HardwareSizeShort.Production>16</param.HardwareSizeShort.Production>
|
||||
<param.HardwareSizeInt.Production>32</param.HardwareSizeInt.Production>
|
||||
<param.HardwareSizeLong.Production>32</param.HardwareSizeLong.Production>
|
||||
<param.HardwareSizeLongLong.Production>64</param.HardwareSizeLongLong.Production>
|
||||
<param.HardwareSizeFloat.Production>32</param.HardwareSizeFloat.Production>
|
||||
<param.HardwareSizeDouble.Production>64</param.HardwareSizeDouble.Production>
|
||||
<param.HardwareSizeWord.Production>32</param.HardwareSizeWord.Production>
|
||||
<param.HardwareSizePointer.Production>32</param.HardwareSizePointer.Production>
|
||||
<param.HardwareEndianness.Production>option.HardwareEndianness.Little</param.HardwareEndianness.Production>
|
||||
<param.HardwareArithmeticRightShift.Production>true</param.HardwareArithmeticRightShift.Production>
|
||||
<param.HardwareLongLongMode.Production>false</param.HardwareLongLongMode.Production>
|
||||
<param.HardwareAtomicIntegerSize.Production>option.HardwareAtomicIntegerSize.Long</param.HardwareAtomicIntegerSize.Production>
|
||||
<param.HardwareAtomicFloatSize.Production>option.HardwareAtomicFloatSize.Double</param.HardwareAtomicFloatSize.Production>
|
||||
<param.HardwareDivisionRounding.Production>option.HardwareDivisionRounding.Undefined</param.HardwareDivisionRounding.Production>
|
||||
<param.HardwareVendor.Target>Generic</param.HardwareVendor.Target>
|
||||
<param.HardwareType.Target>MATLAB Host Computer</param.HardwareType.Target>
|
||||
<var.instance.enabled.Target>false</var.instance.enabled.Target>
|
||||
<param.HardwareSizeChar.Target>8</param.HardwareSizeChar.Target>
|
||||
<param.HardwareSizeShort.Target>16</param.HardwareSizeShort.Target>
|
||||
<param.HardwareSizeInt.Target>32</param.HardwareSizeInt.Target>
|
||||
<param.HardwareSizeLong.Target>64</param.HardwareSizeLong.Target>
|
||||
<param.HardwareSizeLongLong.Target>64</param.HardwareSizeLongLong.Target>
|
||||
<param.HardwareSizeFloat.Target>32</param.HardwareSizeFloat.Target>
|
||||
<param.HardwareSizeDouble.Target>64</param.HardwareSizeDouble.Target>
|
||||
<param.HardwareSizeWord.Target>64</param.HardwareSizeWord.Target>
|
||||
<param.HardwareSizePointer.Target>64</param.HardwareSizePointer.Target>
|
||||
<param.HardwareEndianness.Target>option.HardwareEndianness.Little</param.HardwareEndianness.Target>
|
||||
<param.HardwareArithmeticRightShift.Target>true</param.HardwareArithmeticRightShift.Target>
|
||||
<param.HardwareLongLongMode.Target>true</param.HardwareLongLongMode.Target>
|
||||
<param.HardwareAtomicIntegerSize.Target>option.HardwareAtomicIntegerSize.Char</param.HardwareAtomicIntegerSize.Target>
|
||||
<param.HardwareAtomicFloatSize.Target>option.HardwareAtomicFloatSize.None</param.HardwareAtomicFloatSize.Target>
|
||||
<param.HardwareDivisionRounding.Target>option.HardwareDivisionRounding.Zero</param.HardwareDivisionRounding.Target>
|
||||
<param.Toolchain>Automatically locate an installed toolchain</param.Toolchain>
|
||||
<param.BuildConfiguration>Faster Builds</param.BuildConfiguration>
|
||||
<param.CustomToolchainOptions />
|
||||
<param.ConstantFoldingTimeout>40000</param.ConstantFoldingTimeout>
|
||||
<param.RecursionLimit>100</param.RecursionLimit>
|
||||
<param.IncludeTerminateFcn>true</param.IncludeTerminateFcn>
|
||||
<param.TargetLang>option.TargetLang.C</param.TargetLang>
|
||||
<param.CCompilerOptimization>option.CCompilerOptimization.On</param.CCompilerOptimization>
|
||||
<param.CCompilerCustomOptimizations />
|
||||
<param.GenerateMakefile>true</param.GenerateMakefile>
|
||||
<param.BuildToolEnable>false</param.BuildToolEnable>
|
||||
<param.MakeCommand>make_rtw</param.MakeCommand>
|
||||
<param.TemplateMakefile>default_tmf</param.TemplateMakefile>
|
||||
<param.BuildToolConfiguration />
|
||||
<param.InlineThreshold>10</param.InlineThreshold>
|
||||
<param.InlineThresholdMax>200</param.InlineThresholdMax>
|
||||
<param.InlineStackLimit>4000</param.InlineStackLimit>
|
||||
<param.EnableMemcpy>true</param.EnableMemcpy>
|
||||
<param.MemcpyThreshold>64</param.MemcpyThreshold>
|
||||
<param.EnableOpenMP>true</param.EnableOpenMP>
|
||||
<param.InitFltsAndDblsToZero>true</param.InitFltsAndDblsToZero>
|
||||
<param.PassStructByReference>false</param.PassStructByReference>
|
||||
<param.UseECoderFeatures>true</param.UseECoderFeatures>
|
||||
<unset>
|
||||
<param.WorkingFolder />
|
||||
<param.SpecifiedWorkingFolder />
|
||||
<param.SearchPaths />
|
||||
<param.SaturateOnIntegerOverflow />
|
||||
<param.PurelyIntegerCode />
|
||||
<param.DynamicMemoryAllocation />
|
||||
<param.DynamicMemoryAllocationThreshold />
|
||||
<param.MultiInstanceCode />
|
||||
<param.GenerateComments />
|
||||
<param.MATLABFcnDesc />
|
||||
<param.DataTypeReplacement />
|
||||
<param.ConvertIfToSwitch />
|
||||
<param.PreserveExternInFcnDecls />
|
||||
<param.ParenthesesLevel />
|
||||
<param.MaxIdLength />
|
||||
<param.CustomSymbolStrGlobalVar />
|
||||
<param.CustomSymbolStrType />
|
||||
<param.CustomSymbolStrField />
|
||||
<param.CustomSymbolStrFcn />
|
||||
<param.CustomSymbolStrTmpVar />
|
||||
<param.CustomSymbolStrMacro />
|
||||
<param.CustomSymbolStrEMXArray />
|
||||
<param.CustomSymbolStrEMXArrayFcn />
|
||||
<param.ReservedNameArray />
|
||||
<param.EnableScreener />
|
||||
<param.Verbose />
|
||||
<param.GenerateReport />
|
||||
<param.GenerateCodeMetricsReport />
|
||||
<param.GenerateCodeReplacementReport />
|
||||
<param.CustomInclude />
|
||||
<param.CustomSource />
|
||||
<param.CustomLibrary />
|
||||
<param.SameHardware />
|
||||
<var.instance.enabled.Production />
|
||||
<param.HardwareSizeChar.Production />
|
||||
<param.HardwareSizeShort.Production />
|
||||
<param.HardwareSizeInt.Production />
|
||||
<param.HardwareSizeLong.Production />
|
||||
<param.HardwareSizeLongLong.Production />
|
||||
<param.HardwareSizeFloat.Production />
|
||||
<param.HardwareSizeDouble.Production />
|
||||
<param.HardwareSizeWord.Production />
|
||||
<param.HardwareSizePointer.Production />
|
||||
<param.HardwareEndianness.Production />
|
||||
<param.HardwareLongLongMode.Production />
|
||||
<param.HardwareDivisionRounding.Production />
|
||||
<var.instance.enabled.Target />
|
||||
<param.HardwareSizeChar.Target />
|
||||
<param.HardwareSizeShort.Target />
|
||||
<param.HardwareSizeInt.Target />
|
||||
<param.HardwareSizeLongLong.Target />
|
||||
<param.HardwareSizeFloat.Target />
|
||||
<param.HardwareSizeDouble.Target />
|
||||
<param.HardwareEndianness.Target />
|
||||
<param.HardwareAtomicFloatSize.Target />
|
||||
<param.CustomToolchainOptions />
|
||||
<param.ConstantFoldingTimeout />
|
||||
<param.RecursionLimit />
|
||||
<param.IncludeTerminateFcn />
|
||||
<param.TargetLang />
|
||||
<param.CCompilerCustomOptimizations />
|
||||
<param.GenerateMakefile />
|
||||
<param.BuildToolEnable />
|
||||
<param.MakeCommand />
|
||||
<param.TemplateMakefile />
|
||||
<param.BuildToolConfiguration />
|
||||
<param.InlineThreshold />
|
||||
<param.InlineThresholdMax />
|
||||
<param.InlineStackLimit />
|
||||
<param.EnableMemcpy />
|
||||
<param.MemcpyThreshold />
|
||||
<param.EnableOpenMP />
|
||||
<param.InitFltsAndDblsToZero />
|
||||
<param.UseECoderFeatures />
|
||||
</unset>
|
||||
</profile>
|
||||
<param.outputfile>/opt/matlab/r2013b/bin/codegen/codegen/lib/AttitudeEKF/AttitudeEKF.a</param.outputfile>
|
||||
<param.version>R2012a</param.version>
|
||||
<param.HasECoderFeatures>true</param.HasECoderFeatures>
|
||||
<param.mex.mainhtml>t:\private\desktop-dinfk-xp\Attitude_Kalmanfilter\codegen\mex\attitudeKalmanfilter\html\index.html</param.mex.mainhtml>
|
||||
<param.grt.mainhtml>/home/thomasgubler/src/Firmware/src/modules/attitude_estimator_ekf/codegen/html/index.html</param.grt.mainhtml>
|
||||
<param.CallGeneratedCodeFromTest>true</param.CallGeneratedCodeFromTest>
|
||||
<param.VerificationMode>option.VerificationMode.None</param.VerificationMode>
|
||||
<param.SILDebugging>false</param.SILDebugging>
|
||||
<param.DefaultTestFile>${PROJECT_ROOT}/AttitudeEKF_Test.m</param.DefaultTestFile>
|
||||
<param.AutoInferDefaultFile>${PROJECT_ROOT}/AttitudeEKF_Test.m</param.AutoInferDefaultFile>
|
||||
<param.AutoInferUseVariableSize>false</param.AutoInferUseVariableSize>
|
||||
<param.AutoInferUseUnboundedSize>false</param.AutoInferUseUnboundedSize>
|
||||
<param.AutoInferVariableSizeThreshold>1024</param.AutoInferVariableSizeThreshold>
|
||||
<param.AutoInferUnboundedSizeThreshold>2048</param.AutoInferUnboundedSizeThreshold>
|
||||
<param.mex.outputfile>AttitudeEKF_mex</param.mex.outputfile>
|
||||
<param.grt.outputfile>AttitudeEKF</param.grt.outputfile>
|
||||
<param.artifact>option.target.artifact.lib</param.artifact>
|
||||
<param.FixedPointTypeProposalMode>option.FixedPointTypeProposalMode.ProposeFractionLengths</param.FixedPointTypeProposalMode>
|
||||
<param.DefaultProposedFixedPointType>numerictype([],16,12)</param.DefaultProposedFixedPointType>
|
||||
<param.MinMaxSafetyMargin>0</param.MinMaxSafetyMargin>
|
||||
<param.OptimizeWholeNumbers>true</param.OptimizeWholeNumbers>
|
||||
<param.LaunchInstrumentationReport>false</param.LaunchInstrumentationReport>
|
||||
<param.OpenInstrumentationReportInBrowser>false</param.OpenInstrumentationReportInBrowser>
|
||||
<param.CreatePrintableInstrumentationReport>false</param.CreatePrintableInstrumentationReport>
|
||||
<param.EnableAutoExtrinsicCalls>true</param.EnableAutoExtrinsicCalls>
|
||||
<param.UsePreconditions>false</param.UsePreconditions>
|
||||
<param.FeatureFlags />
|
||||
<param.FixedPointMode>option.FixedPointMode.None</param.FixedPointMode>
|
||||
<param.AutoScaleLoopIndexVariables>false</param.AutoScaleLoopIndexVariables>
|
||||
<param.ComputedFixedPointData />
|
||||
<param.UserFixedPointData />
|
||||
<param.DefaultWordLength>16</param.DefaultWordLength>
|
||||
<param.DefaultFractionLength>4</param.DefaultFractionLength>
|
||||
<param.FixedPointSafetyMargin>0</param.FixedPointSafetyMargin>
|
||||
<param.FixedPointFimath>fimath('RoundingMethod', 'Floor', 'OverflowAction', 'Wrap', 'ProductMode', 'FullPrecision', 'MaxProductWordLength', 128, 'SumMode', 'FullPrecision', 'MaxSumWordLength', 128)</param.FixedPointFimath>
|
||||
<param.FixedPointTypeSource>option.FixedPointTypeSource.SimAndDerived</param.FixedPointTypeSource>
|
||||
<param.StaticAnalysisTimeout />
|
||||
<param.StaticAnalysisGlobalRangesOnly>false</param.StaticAnalysisGlobalRangesOnly>
|
||||
<param.LogAllIOValues>false</param.LogAllIOValues>
|
||||
<param.LogHistogram>false</param.LogHistogram>
|
||||
<param.ShowCoverage>true</param.ShowCoverage>
|
||||
<param.ExcludedFixedPointVerificationFiles />
|
||||
<param.ExcludedFixedPointSimulationFiles />
|
||||
<param.InstrumentedBuildChecksum />
|
||||
<param.FixedPointStaticAnalysisChecksum />
|
||||
<param.InstrumentedMexFile />
|
||||
<param.FixedPointValidationChecksum />
|
||||
<param.FixedPointSourceCodeChecksum />
|
||||
<param.FixedPointFunctionReplacements />
|
||||
<param.OptimizeWholeNumbers>true</param.OptimizeWholeNumbers>
|
||||
<param.GeneratedFixedPointFileSuffix>_fixpt</param.GeneratedFixedPointFileSuffix>
|
||||
<param.DefaultFixedPointSignedness>option.DefaultFixedPointSignedness.Automatic</param.DefaultFixedPointSignedness>
|
||||
<unset>
|
||||
<param.outputfile />
|
||||
<param.version />
|
||||
<param.HasECoderFeatures />
|
||||
<param.CallGeneratedCodeFromTest />
|
||||
<param.VerificationMode />
|
||||
<param.SILDebugging />
|
||||
<param.AutoInferUseVariableSize />
|
||||
<param.AutoInferUseUnboundedSize />
|
||||
<param.AutoInferVariableSizeThreshold />
|
||||
<param.AutoInferUnboundedSizeThreshold />
|
||||
<param.mex.outputfile />
|
||||
<param.grt.outputfile />
|
||||
<param.FixedPointTypeProposalMode />
|
||||
<param.DefaultProposedFixedPointType />
|
||||
<param.MinMaxSafetyMargin />
|
||||
<param.OptimizeWholeNumbers />
|
||||
<param.LaunchInstrumentationReport />
|
||||
<param.OpenInstrumentationReportInBrowser />
|
||||
<param.CreatePrintableInstrumentationReport />
|
||||
<param.EnableAutoExtrinsicCalls />
|
||||
<param.UsePreconditions />
|
||||
<param.FeatureFlags />
|
||||
<param.FixedPointMode />
|
||||
<param.AutoScaleLoopIndexVariables />
|
||||
<param.ComputedFixedPointData />
|
||||
<param.UserFixedPointData />
|
||||
<param.DefaultWordLength />
|
||||
<param.DefaultFractionLength />
|
||||
<param.FixedPointSafetyMargin />
|
||||
<param.FixedPointFimath />
|
||||
<param.FixedPointTypeSource />
|
||||
<param.StaticAnalysisTimeout />
|
||||
<param.StaticAnalysisGlobalRangesOnly />
|
||||
<param.LogAllIOValues />
|
||||
<param.LogHistogram />
|
||||
<param.ShowCoverage />
|
||||
<param.ExcludedFixedPointVerificationFiles />
|
||||
<param.ExcludedFixedPointSimulationFiles />
|
||||
<param.InstrumentedBuildChecksum />
|
||||
<param.FixedPointStaticAnalysisChecksum />
|
||||
<param.InstrumentedMexFile />
|
||||
<param.FixedPointValidationChecksum />
|
||||
<param.FixedPointSourceCodeChecksum />
|
||||
<param.FixedPointFunctionReplacements />
|
||||
<param.GeneratedFixedPointFileSuffix />
|
||||
<param.DefaultFixedPointSignedness />
|
||||
</unset>
|
||||
<fileset.entrypoints>
|
||||
<file value="${PROJECT_ROOT}/AttitudeEKF.m" custom-data-expanded="true">
|
||||
<Inputs fileName="AttitudeEKF.m" functionName="AttitudeEKF">
|
||||
<Input Name="approx_prediction">
|
||||
<Class>uint8</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="use_inertia_matrix">
|
||||
<Class>uint8</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="zFlag">
|
||||
<Class>uint8</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>3 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="dt">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="z">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>9 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="q_rotSpeed">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="q_rotAcc">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="q_acc">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="q_mag">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="r_gyro">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="r_accel">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="r_mag">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>1 x 1</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
<Input Name="J">
|
||||
<Class>single</Class>
|
||||
<UserDefined>false</UserDefined>
|
||||
<Size>3 x 3</Size>
|
||||
<Complex>false</Complex>
|
||||
</Input>
|
||||
</Inputs>
|
||||
</file>
|
||||
</fileset.entrypoints>
|
||||
<fileset.testbench>
|
||||
<file>${PROJECT_ROOT}/AttitudeEKF_Test.m</file>
|
||||
</fileset.testbench>
|
||||
<fileset.package />
|
||||
<build-deliverables>
|
||||
<file name="AttitudeEKF.a" location="${MATLAB_ROOT}/bin/codegen/codegen/lib/AttitudeEKF" optional="false">/opt/matlab/r2013b/bin/codegen/codegen/lib/AttitudeEKF/AttitudeEKF.a</file>
|
||||
</build-deliverables>
|
||||
<workflow />
|
||||
<matlab>
|
||||
<root>/opt/matlab/r2013b</root>
|
||||
<toolboxes>
|
||||
<toolbox name="fixedpoint" />
|
||||
</toolboxes>
|
||||
</matlab>
|
||||
<platform>
|
||||
<unix>true</unix>
|
||||
<mac>false</mac>
|
||||
<windows>false</windows>
|
||||
<win2k>false</win2k>
|
||||
<winxp>false</winxp>
|
||||
<vista>false</vista>
|
||||
<linux>true</linux>
|
||||
<solaris>false</solaris>
|
||||
<osver>3.16.1-1-ARCH</osver>
|
||||
<os32>false</os32>
|
||||
<os64>true</os64>
|
||||
<arch>glnxa64</arch>
|
||||
<matlab>true</matlab>
|
||||
</platform>
|
||||
</configuration>
|
||||
</deployment-project>
|
||||
|
||||
@@ -38,6 +38,7 @@
|
||||
*
|
||||
* @author Tobias Naegeli <naegelit@student.ethz.ch>
|
||||
* @author Lorenz Meier <lm@inf.ethz.ch>
|
||||
* @author Thomas Gubler <thomasgubler@gmail.com>
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
@@ -74,8 +75,7 @@
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
#include "codegen/attitudeKalmanfilter_initialize.h"
|
||||
#include "codegen/attitudeKalmanfilter.h"
|
||||
#include "codegen/AttitudeEKF.h"
|
||||
#include "attitude_estimator_ekf_params.h"
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
@@ -132,7 +132,7 @@ int attitude_estimator_ekf_main(int argc, char *argv[])
|
||||
attitude_estimator_ekf_task = task_spawn_cmd("attitude_estimator_ekf",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 5,
|
||||
14000,
|
||||
7200,
|
||||
attitude_estimator_ekf_thread_main,
|
||||
(argv) ? (const char **)&argv[2] : (const char **)NULL);
|
||||
exit(0);
|
||||
@@ -206,14 +206,12 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||
0, 0, 1.f
|
||||
}; /**< init: identity matrix */
|
||||
|
||||
// print text
|
||||
printf("Extended Kalman Filter Attitude Estimator initialized..\n\n");
|
||||
fflush(stdout);
|
||||
float debugOutput[4] = { 0.0f };
|
||||
|
||||
int overloadcounter = 19;
|
||||
|
||||
/* Initialize filter */
|
||||
attitudeKalmanfilter_initialize();
|
||||
AttitudeEKF_initialize();
|
||||
|
||||
/* store start time to guard against too slow update rates */
|
||||
uint64_t last_run = hrt_absolute_time();
|
||||
@@ -277,9 +275,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||
/* keep track of sensor updates */
|
||||
uint64_t sensor_last_timestamp[3] = {0, 0, 0};
|
||||
|
||||
struct attitude_estimator_ekf_params ekf_params;
|
||||
struct attitude_estimator_ekf_params ekf_params = { 0 };
|
||||
|
||||
struct attitude_estimator_ekf_param_handles ekf_param_handles;
|
||||
struct attitude_estimator_ekf_param_handles ekf_param_handles = { 0 };
|
||||
|
||||
/* initialize parameter handles */
|
||||
parameters_init(&ekf_param_handles);
|
||||
@@ -508,8 +506,25 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||
continue;
|
||||
}
|
||||
|
||||
attitudeKalmanfilter(update_vect, dt, z_k, x_aposteriori_k, P_aposteriori_k, ekf_params.q, ekf_params.r,
|
||||
euler, Rot_matrix, x_aposteriori, P_aposteriori);
|
||||
/* Call the estimator */
|
||||
AttitudeEKF(false, // approx_prediction
|
||||
(unsigned char)ekf_params.use_moment_inertia,
|
||||
update_vect,
|
||||
dt,
|
||||
z_k,
|
||||
ekf_params.q[0], // q_rotSpeed,
|
||||
ekf_params.q[1], // q_rotAcc
|
||||
ekf_params.q[2], // q_acc
|
||||
ekf_params.q[3], // q_mag
|
||||
ekf_params.r[0], // r_gyro
|
||||
ekf_params.r[1], // r_accel
|
||||
ekf_params.r[2], // r_mag
|
||||
ekf_params.moment_inertia_J,
|
||||
x_aposteriori,
|
||||
P_aposteriori,
|
||||
Rot_matrix,
|
||||
euler,
|
||||
debugOutput);
|
||||
|
||||
/* swap values for next iteration, check for fatal inputs */
|
||||
if (isfinite(euler[0]) && isfinite(euler[1]) && isfinite(euler[2])) {
|
||||
|
||||
@@ -44,28 +44,96 @@
|
||||
|
||||
/* Extended Kalman Filter covariances */
|
||||
|
||||
/* gyro process noise */
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q0, 1e-4f);
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q1, 0.08f);
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q2, 0.009f);
|
||||
/* gyro offsets process noise */
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q3, 0.005f);
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q4, 0.0f);
|
||||
|
||||
/* gyro measurement noise */
|
||||
/**
|
||||
* Body angular rate process noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q0, 1e-4f);
|
||||
|
||||
/**
|
||||
* Body angular acceleration process noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q1, 0.08f);
|
||||
|
||||
/**
|
||||
* Acceleration process noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q2, 0.009f);
|
||||
|
||||
/**
|
||||
* Magnet field vector process noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V3_Q3, 0.005f);
|
||||
|
||||
/**
|
||||
* Gyro measurement noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V4_R0, 0.0008f);
|
||||
/* accel measurement noise */
|
||||
|
||||
/**
|
||||
* Accel measurement noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V4_R1, 10000.0f);
|
||||
/* mag measurement noise */
|
||||
|
||||
/**
|
||||
* Mag measurement noise
|
||||
*
|
||||
* @group attitude_ekf
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V4_R2, 100.0f);
|
||||
/* offset estimation - UNUSED */
|
||||
PARAM_DEFINE_FLOAT(EKF_ATT_V4_R3, 0.0f);
|
||||
|
||||
/* magnetic declination, in degrees */
|
||||
PARAM_DEFINE_FLOAT(ATT_MAG_DECL, 0.0f);
|
||||
|
||||
PARAM_DEFINE_INT32(ATT_ACC_COMP, 2);
|
||||
|
||||
/**
|
||||
* Moment of inertia matrix diagonal entry (1, 1)
|
||||
*
|
||||
* @group attitude_ekf
|
||||
* @unit kg*m^2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(ATT_J11, 0.0018);
|
||||
|
||||
/**
|
||||
* Moment of inertia matrix diagonal entry (2, 2)
|
||||
*
|
||||
* @group attitude_ekf
|
||||
* @unit kg*m^2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(ATT_J22, 0.0018);
|
||||
|
||||
/**
|
||||
* Moment of inertia matrix diagonal entry (3, 3)
|
||||
*
|
||||
* @group attitude_ekf
|
||||
* @unit kg*m^2
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(ATT_J33, 0.0037);
|
||||
|
||||
/**
|
||||
* Moment of inertia enabled in estimator
|
||||
*
|
||||
* If set to != 0 the moment of inertia will be used in the estimator
|
||||
*
|
||||
* @group attitude_ekf
|
||||
* @min 0
|
||||
* @max 1
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ATT_J_EN, 0);
|
||||
|
||||
int parameters_init(struct attitude_estimator_ekf_param_handles *h)
|
||||
{
|
||||
/* PID parameters */
|
||||
@@ -73,17 +141,20 @@ int parameters_init(struct attitude_estimator_ekf_param_handles *h)
|
||||
h->q1 = param_find("EKF_ATT_V3_Q1");
|
||||
h->q2 = param_find("EKF_ATT_V3_Q2");
|
||||
h->q3 = param_find("EKF_ATT_V3_Q3");
|
||||
h->q4 = param_find("EKF_ATT_V3_Q4");
|
||||
|
||||
h->r0 = param_find("EKF_ATT_V4_R0");
|
||||
h->r1 = param_find("EKF_ATT_V4_R1");
|
||||
h->r2 = param_find("EKF_ATT_V4_R2");
|
||||
h->r3 = param_find("EKF_ATT_V4_R3");
|
||||
|
||||
h->mag_decl = param_find("ATT_MAG_DECL");
|
||||
|
||||
h->acc_comp = param_find("ATT_ACC_COMP");
|
||||
|
||||
h->moment_inertia_J[0] = param_find("ATT_J11");
|
||||
h->moment_inertia_J[1] = param_find("ATT_J22");
|
||||
h->moment_inertia_J[2] = param_find("ATT_J33");
|
||||
h->use_moment_inertia = param_find("ATT_J_EN");
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -93,17 +164,20 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
|
||||
param_get(h->q1, &(p->q[1]));
|
||||
param_get(h->q2, &(p->q[2]));
|
||||
param_get(h->q3, &(p->q[3]));
|
||||
param_get(h->q4, &(p->q[4]));
|
||||
|
||||
param_get(h->r0, &(p->r[0]));
|
||||
param_get(h->r1, &(p->r[1]));
|
||||
param_get(h->r2, &(p->r[2]));
|
||||
param_get(h->r3, &(p->r[3]));
|
||||
|
||||
param_get(h->mag_decl, &(p->mag_decl));
|
||||
p->mag_decl *= M_PI_F / 180.0f;
|
||||
|
||||
param_get(h->acc_comp, &(p->acc_comp));
|
||||
|
||||
for (int i = 0; i < 3; i++) {
|
||||
param_get(h->moment_inertia_J[i], &(p->moment_inertia_J[3 * i + i]));
|
||||
}
|
||||
param_get(h->use_moment_inertia, &(p->use_moment_inertia));
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
@@ -42,8 +42,10 @@
|
||||
#include <systemlib/param/param.h>
|
||||
|
||||
struct attitude_estimator_ekf_params {
|
||||
float r[9];
|
||||
float q[12];
|
||||
float r[3];
|
||||
float q[4];
|
||||
float moment_inertia_J[9];
|
||||
int32_t use_moment_inertia;
|
||||
float roll_off;
|
||||
float pitch_off;
|
||||
float yaw_off;
|
||||
@@ -52,8 +54,10 @@ struct attitude_estimator_ekf_params {
|
||||
};
|
||||
|
||||
struct attitude_estimator_ekf_param_handles {
|
||||
param_t r0, r1, r2, r3;
|
||||
param_t q0, q1, q2, q3, q4;
|
||||
param_t r0, r1, r2;
|
||||
param_t q0, q1, q2, q3;
|
||||
param_t moment_inertia_J[3]; /**< diagonal entries of the matrix */
|
||||
param_t use_moment_inertia;
|
||||
param_t mag_decl;
|
||||
param_t acc_comp;
|
||||
};
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,26 @@
|
||||
/*
|
||||
* AttitudeEKF.h
|
||||
*
|
||||
* Code generation for function 'AttitudeEKF'
|
||||
*
|
||||
* C source code generated on: Thu Aug 21 11:17:28 2014
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEEKF_H__
|
||||
#define __ATTITUDEEKF_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "AttitudeEKF_types.h"
|
||||
|
||||
/* Function Declarations */
|
||||
extern void AttitudeEKF(unsigned char approx_prediction, unsigned char use_inertia_matrix, const unsigned char zFlag[3], float dt, const float z[9], float q_rotSpeed, float q_rotAcc, float q_acc, float q_mag, float r_gyro, float r_accel, float r_mag, const float J[9], float xa_apo[12], float Pa_apo[144], float Rot_matrix[9], float eulerAngles[3], float debugOutput[4]);
|
||||
extern void AttitudeEKF_initialize(void);
|
||||
extern void AttitudeEKF_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (AttitudeEKF.h) */
|
||||
@@ -0,0 +1,17 @@
|
||||
/*
|
||||
* AttitudeEKF_types.h
|
||||
*
|
||||
* Code generation for function 'AttitudeEKF'
|
||||
*
|
||||
* C source code generated on: Thu Aug 21 11:17:28 2014
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEEKF_TYPES_H__
|
||||
#define __ATTITUDEEKF_TYPES_H__
|
||||
|
||||
/* Include files */
|
||||
#include "rtwtypes.h"
|
||||
|
||||
#endif
|
||||
/* End of code generation (AttitudeEKF_types.h) */
|
||||
File diff suppressed because it is too large
Load Diff
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEKALMANFILTER_H__
|
||||
#define __ATTITUDEKALMANFILTER_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void attitudeKalmanfilter(const uint8_T updateVect[3], real32_T dt, const real32_T z[9], const real32_T x_aposteriori_k[12], const real32_T P_aposteriori_k[144], const real32_T q[12], real32_T r[9], real32_T eulerAngles[3], real32_T Rot_matrix[9], real32_T x_aposteriori[12], real32_T P_aposteriori[144]);
|
||||
#endif
|
||||
/* End of code generation (attitudeKalmanfilter.h) */
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter_initialize.c
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter_initialize'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "attitudeKalmanfilter_initialize.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void attitudeKalmanfilter_initialize(void)
|
||||
{
|
||||
rt_InitInfAndNaN(8U);
|
||||
}
|
||||
|
||||
/* End of code generation (attitudeKalmanfilter_initialize.c) */
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter_initialize.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter_initialize'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEKALMANFILTER_INITIALIZE_H__
|
||||
#define __ATTITUDEKALMANFILTER_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void attitudeKalmanfilter_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (attitudeKalmanfilter_initialize.h) */
|
||||
@@ -1,31 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter_terminate.c
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter_terminate'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "attitudeKalmanfilter_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void attitudeKalmanfilter_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (attitudeKalmanfilter_terminate.c) */
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter_terminate.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter_terminate'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEKALMANFILTER_TERMINATE_H__
|
||||
#define __ATTITUDEKALMANFILTER_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void attitudeKalmanfilter_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (attitudeKalmanfilter_terminate.h) */
|
||||
@@ -1,16 +0,0 @@
|
||||
/*
|
||||
* attitudeKalmanfilter_types.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __ATTITUDEKALMANFILTER_TYPES_H__
|
||||
#define __ATTITUDEKALMANFILTER_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (attitudeKalmanfilter_types.h) */
|
||||
@@ -1,37 +0,0 @@
|
||||
/*
|
||||
* cross.c
|
||||
*
|
||||
* Code generation for function 'cross'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "cross.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void cross(const real32_T a[3], const real32_T b[3], real32_T c[3])
|
||||
{
|
||||
c[0] = a[1] * b[2] - a[2] * b[1];
|
||||
c[1] = a[2] * b[0] - a[0] * b[2];
|
||||
c[2] = a[0] * b[1] - a[1] * b[0];
|
||||
}
|
||||
|
||||
/* End of code generation (cross.c) */
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* cross.h
|
||||
*
|
||||
* Code generation for function 'cross'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __CROSS_H__
|
||||
#define __CROSS_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void cross(const real32_T a[3], const real32_T b[3], real32_T c[3]);
|
||||
#endif
|
||||
/* End of code generation (cross.h) */
|
||||
@@ -1,51 +0,0 @@
|
||||
/*
|
||||
* eye.c
|
||||
*
|
||||
* Code generation for function 'eye'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "eye.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void b_eye(real_T I[144])
|
||||
{
|
||||
int32_T i;
|
||||
memset(&I[0], 0, 144U * sizeof(real_T));
|
||||
for (i = 0; i < 12; i++) {
|
||||
I[i + 12 * i] = 1.0;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void eye(real_T I[9])
|
||||
{
|
||||
int32_T i;
|
||||
memset(&I[0], 0, 9U * sizeof(real_T));
|
||||
for (i = 0; i < 3; i++) {
|
||||
I[i + 3 * i] = 1.0;
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (eye.c) */
|
||||
@@ -1,35 +0,0 @@
|
||||
/*
|
||||
* eye.h
|
||||
*
|
||||
* Code generation for function 'eye'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __EYE_H__
|
||||
#define __EYE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void b_eye(real_T I[144]);
|
||||
extern void eye(real_T I[9]);
|
||||
#endif
|
||||
/* End of code generation (eye.h) */
|
||||
@@ -1,357 +0,0 @@
|
||||
/*
|
||||
* mrdivide.c
|
||||
*
|
||||
* Code generation for function 'mrdivide'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "mrdivide.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void b_mrdivide(const real32_T A[36], const real32_T B[9], real32_T y[36])
|
||||
{
|
||||
real32_T b_A[9];
|
||||
int32_T rtemp;
|
||||
int32_T k;
|
||||
real32_T b_B[36];
|
||||
int32_T r1;
|
||||
int32_T r2;
|
||||
int32_T r3;
|
||||
real32_T maxval;
|
||||
real32_T a21;
|
||||
real32_T Y[36];
|
||||
for (rtemp = 0; rtemp < 3; rtemp++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
b_A[k + 3 * rtemp] = B[rtemp + 3 * k];
|
||||
}
|
||||
}
|
||||
|
||||
for (rtemp = 0; rtemp < 12; rtemp++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
b_B[k + 3 * rtemp] = A[rtemp + 12 * k];
|
||||
}
|
||||
}
|
||||
|
||||
r1 = 0;
|
||||
r2 = 1;
|
||||
r3 = 2;
|
||||
maxval = (real32_T)fabs(b_A[0]);
|
||||
a21 = (real32_T)fabs(b_A[1]);
|
||||
if (a21 > maxval) {
|
||||
maxval = a21;
|
||||
r1 = 1;
|
||||
r2 = 0;
|
||||
}
|
||||
|
||||
if ((real32_T)fabs(b_A[2]) > maxval) {
|
||||
r1 = 2;
|
||||
r2 = 1;
|
||||
r3 = 0;
|
||||
}
|
||||
|
||||
b_A[r2] /= b_A[r1];
|
||||
b_A[r3] /= b_A[r1];
|
||||
b_A[3 + r2] -= b_A[r2] * b_A[3 + r1];
|
||||
b_A[3 + r3] -= b_A[r3] * b_A[3 + r1];
|
||||
b_A[6 + r2] -= b_A[r2] * b_A[6 + r1];
|
||||
b_A[6 + r3] -= b_A[r3] * b_A[6 + r1];
|
||||
if ((real32_T)fabs(b_A[3 + r3]) > (real32_T)fabs(b_A[3 + r2])) {
|
||||
rtemp = r2;
|
||||
r2 = r3;
|
||||
r3 = rtemp;
|
||||
}
|
||||
|
||||
b_A[3 + r3] /= b_A[3 + r2];
|
||||
b_A[6 + r3] -= b_A[3 + r3] * b_A[6 + r2];
|
||||
for (k = 0; k < 12; k++) {
|
||||
Y[3 * k] = b_B[r1 + 3 * k];
|
||||
Y[1 + 3 * k] = b_B[r2 + 3 * k] - Y[3 * k] * b_A[r2];
|
||||
Y[2 + 3 * k] = (b_B[r3 + 3 * k] - Y[3 * k] * b_A[r3]) - Y[1 + 3 * k] * b_A[3
|
||||
+ r3];
|
||||
Y[2 + 3 * k] /= b_A[6 + r3];
|
||||
Y[3 * k] -= Y[2 + 3 * k] * b_A[6 + r1];
|
||||
Y[1 + 3 * k] -= Y[2 + 3 * k] * b_A[6 + r2];
|
||||
Y[1 + 3 * k] /= b_A[3 + r2];
|
||||
Y[3 * k] -= Y[1 + 3 * k] * b_A[3 + r1];
|
||||
Y[3 * k] /= b_A[r1];
|
||||
}
|
||||
|
||||
for (rtemp = 0; rtemp < 3; rtemp++) {
|
||||
for (k = 0; k < 12; k++) {
|
||||
y[k + 12 * rtemp] = Y[rtemp + 3 * k];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void c_mrdivide(const real32_T A[72], const real32_T B[36], real32_T y[72])
|
||||
{
|
||||
real32_T b_A[36];
|
||||
int8_T ipiv[6];
|
||||
int32_T i3;
|
||||
int32_T iy;
|
||||
int32_T j;
|
||||
int32_T c;
|
||||
int32_T ix;
|
||||
real32_T temp;
|
||||
int32_T k;
|
||||
real32_T s;
|
||||
int32_T jy;
|
||||
int32_T ijA;
|
||||
real32_T Y[72];
|
||||
for (i3 = 0; i3 < 6; i3++) {
|
||||
for (iy = 0; iy < 6; iy++) {
|
||||
b_A[iy + 6 * i3] = B[i3 + 6 * iy];
|
||||
}
|
||||
|
||||
ipiv[i3] = (int8_T)(1 + i3);
|
||||
}
|
||||
|
||||
for (j = 0; j < 5; j++) {
|
||||
c = j * 7;
|
||||
iy = 0;
|
||||
ix = c;
|
||||
temp = (real32_T)fabs(b_A[c]);
|
||||
for (k = 2; k <= 6 - j; k++) {
|
||||
ix++;
|
||||
s = (real32_T)fabs(b_A[ix]);
|
||||
if (s > temp) {
|
||||
iy = k - 1;
|
||||
temp = s;
|
||||
}
|
||||
}
|
||||
|
||||
if (b_A[c + iy] != 0.0F) {
|
||||
if (iy != 0) {
|
||||
ipiv[j] = (int8_T)((j + iy) + 1);
|
||||
ix = j;
|
||||
iy += j;
|
||||
for (k = 0; k < 6; k++) {
|
||||
temp = b_A[ix];
|
||||
b_A[ix] = b_A[iy];
|
||||
b_A[iy] = temp;
|
||||
ix += 6;
|
||||
iy += 6;
|
||||
}
|
||||
}
|
||||
|
||||
i3 = (c - j) + 6;
|
||||
for (jy = c + 1; jy + 1 <= i3; jy++) {
|
||||
b_A[jy] /= b_A[c];
|
||||
}
|
||||
}
|
||||
|
||||
iy = c;
|
||||
jy = c + 6;
|
||||
for (k = 1; k <= 5 - j; k++) {
|
||||
temp = b_A[jy];
|
||||
if (b_A[jy] != 0.0F) {
|
||||
ix = c + 1;
|
||||
i3 = (iy - j) + 12;
|
||||
for (ijA = 7 + iy; ijA + 1 <= i3; ijA++) {
|
||||
b_A[ijA] += b_A[ix] * -temp;
|
||||
ix++;
|
||||
}
|
||||
}
|
||||
|
||||
jy += 6;
|
||||
iy += 6;
|
||||
}
|
||||
}
|
||||
|
||||
for (i3 = 0; i3 < 12; i3++) {
|
||||
for (iy = 0; iy < 6; iy++) {
|
||||
Y[iy + 6 * i3] = A[i3 + 12 * iy];
|
||||
}
|
||||
}
|
||||
|
||||
for (jy = 0; jy < 6; jy++) {
|
||||
if (ipiv[jy] != jy + 1) {
|
||||
for (j = 0; j < 12; j++) {
|
||||
temp = Y[jy + 6 * j];
|
||||
Y[jy + 6 * j] = Y[(ipiv[jy] + 6 * j) - 1];
|
||||
Y[(ipiv[jy] + 6 * j) - 1] = temp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (j = 0; j < 12; j++) {
|
||||
c = 6 * j;
|
||||
for (k = 0; k < 6; k++) {
|
||||
iy = 6 * k;
|
||||
if (Y[k + c] != 0.0F) {
|
||||
for (jy = k + 2; jy < 7; jy++) {
|
||||
Y[(jy + c) - 1] -= Y[k + c] * b_A[(jy + iy) - 1];
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (j = 0; j < 12; j++) {
|
||||
c = 6 * j;
|
||||
for (k = 5; k > -1; k += -1) {
|
||||
iy = 6 * k;
|
||||
if (Y[k + c] != 0.0F) {
|
||||
Y[k + c] /= b_A[k + iy];
|
||||
for (jy = 0; jy + 1 <= k; jy++) {
|
||||
Y[jy + c] -= Y[k + c] * b_A[jy + iy];
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (i3 = 0; i3 < 6; i3++) {
|
||||
for (iy = 0; iy < 12; iy++) {
|
||||
y[iy + 12 * i3] = Y[i3 + 6 * iy];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void mrdivide(const real32_T A[108], const real32_T B[81], real32_T y[108])
|
||||
{
|
||||
real32_T b_A[81];
|
||||
int8_T ipiv[9];
|
||||
int32_T i2;
|
||||
int32_T iy;
|
||||
int32_T j;
|
||||
int32_T c;
|
||||
int32_T ix;
|
||||
real32_T temp;
|
||||
int32_T k;
|
||||
real32_T s;
|
||||
int32_T jy;
|
||||
int32_T ijA;
|
||||
real32_T Y[108];
|
||||
for (i2 = 0; i2 < 9; i2++) {
|
||||
for (iy = 0; iy < 9; iy++) {
|
||||
b_A[iy + 9 * i2] = B[i2 + 9 * iy];
|
||||
}
|
||||
|
||||
ipiv[i2] = (int8_T)(1 + i2);
|
||||
}
|
||||
|
||||
for (j = 0; j < 8; j++) {
|
||||
c = j * 10;
|
||||
iy = 0;
|
||||
ix = c;
|
||||
temp = (real32_T)fabs(b_A[c]);
|
||||
for (k = 2; k <= 9 - j; k++) {
|
||||
ix++;
|
||||
s = (real32_T)fabs(b_A[ix]);
|
||||
if (s > temp) {
|
||||
iy = k - 1;
|
||||
temp = s;
|
||||
}
|
||||
}
|
||||
|
||||
if (b_A[c + iy] != 0.0F) {
|
||||
if (iy != 0) {
|
||||
ipiv[j] = (int8_T)((j + iy) + 1);
|
||||
ix = j;
|
||||
iy += j;
|
||||
for (k = 0; k < 9; k++) {
|
||||
temp = b_A[ix];
|
||||
b_A[ix] = b_A[iy];
|
||||
b_A[iy] = temp;
|
||||
ix += 9;
|
||||
iy += 9;
|
||||
}
|
||||
}
|
||||
|
||||
i2 = (c - j) + 9;
|
||||
for (jy = c + 1; jy + 1 <= i2; jy++) {
|
||||
b_A[jy] /= b_A[c];
|
||||
}
|
||||
}
|
||||
|
||||
iy = c;
|
||||
jy = c + 9;
|
||||
for (k = 1; k <= 8 - j; k++) {
|
||||
temp = b_A[jy];
|
||||
if (b_A[jy] != 0.0F) {
|
||||
ix = c + 1;
|
||||
i2 = (iy - j) + 18;
|
||||
for (ijA = 10 + iy; ijA + 1 <= i2; ijA++) {
|
||||
b_A[ijA] += b_A[ix] * -temp;
|
||||
ix++;
|
||||
}
|
||||
}
|
||||
|
||||
jy += 9;
|
||||
iy += 9;
|
||||
}
|
||||
}
|
||||
|
||||
for (i2 = 0; i2 < 12; i2++) {
|
||||
for (iy = 0; iy < 9; iy++) {
|
||||
Y[iy + 9 * i2] = A[i2 + 12 * iy];
|
||||
}
|
||||
}
|
||||
|
||||
for (jy = 0; jy < 9; jy++) {
|
||||
if (ipiv[jy] != jy + 1) {
|
||||
for (j = 0; j < 12; j++) {
|
||||
temp = Y[jy + 9 * j];
|
||||
Y[jy + 9 * j] = Y[(ipiv[jy] + 9 * j) - 1];
|
||||
Y[(ipiv[jy] + 9 * j) - 1] = temp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (j = 0; j < 12; j++) {
|
||||
c = 9 * j;
|
||||
for (k = 0; k < 9; k++) {
|
||||
iy = 9 * k;
|
||||
if (Y[k + c] != 0.0F) {
|
||||
for (jy = k + 2; jy < 10; jy++) {
|
||||
Y[(jy + c) - 1] -= Y[k + c] * b_A[(jy + iy) - 1];
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (j = 0; j < 12; j++) {
|
||||
c = 9 * j;
|
||||
for (k = 8; k > -1; k += -1) {
|
||||
iy = 9 * k;
|
||||
if (Y[k + c] != 0.0F) {
|
||||
Y[k + c] /= b_A[k + iy];
|
||||
for (jy = 0; jy + 1 <= k; jy++) {
|
||||
Y[jy + c] -= Y[k + c] * b_A[jy + iy];
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (i2 = 0; i2 < 9; i2++) {
|
||||
for (iy = 0; iy < 12; iy++) {
|
||||
y[iy + 12 * i2] = Y[i2 + 9 * iy];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (mrdivide.c) */
|
||||
@@ -1,36 +0,0 @@
|
||||
/*
|
||||
* mrdivide.h
|
||||
*
|
||||
* Code generation for function 'mrdivide'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __MRDIVIDE_H__
|
||||
#define __MRDIVIDE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void b_mrdivide(const real32_T A[36], const real32_T B[9], real32_T y[36]);
|
||||
extern void c_mrdivide(const real32_T A[72], const real32_T B[36], real32_T y[72]);
|
||||
extern void mrdivide(const real32_T A[108], const real32_T B[81], real32_T y[108]);
|
||||
#endif
|
||||
/* End of code generation (mrdivide.h) */
|
||||
@@ -1,54 +0,0 @@
|
||||
/*
|
||||
* norm.c
|
||||
*
|
||||
* Code generation for function 'norm'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "norm.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
real32_T norm(const real32_T x[3])
|
||||
{
|
||||
real32_T y;
|
||||
real32_T scale;
|
||||
int32_T k;
|
||||
real32_T absxk;
|
||||
real32_T t;
|
||||
y = 0.0F;
|
||||
scale = 1.17549435E-38F;
|
||||
for (k = 0; k < 3; k++) {
|
||||
absxk = (real32_T)fabs(x[k]);
|
||||
if (absxk > scale) {
|
||||
t = scale / absxk;
|
||||
y = 1.0F + y * t * t;
|
||||
scale = absxk;
|
||||
} else {
|
||||
t = absxk / scale;
|
||||
y += t * t;
|
||||
}
|
||||
}
|
||||
|
||||
return scale * (real32_T)sqrt(y);
|
||||
}
|
||||
|
||||
/* End of code generation (norm.c) */
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* norm.h
|
||||
*
|
||||
* Code generation for function 'norm'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __NORM_H__
|
||||
#define __NORM_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern real32_T norm(const real32_T x[3]);
|
||||
#endif
|
||||
/* End of code generation (norm.h) */
|
||||
@@ -1,38 +0,0 @@
|
||||
/*
|
||||
* rdivide.c
|
||||
*
|
||||
* Code generation for function 'rdivide'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "attitudeKalmanfilter.h"
|
||||
#include "rdivide.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
|
||||
/*
|
||||
*
|
||||
*/
|
||||
void rdivide(const real32_T x[3], real32_T y, real32_T z[3])
|
||||
{
|
||||
int32_T i;
|
||||
for (i = 0; i < 3; i++) {
|
||||
z[i] = x[i] / y;
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (rdivide.c) */
|
||||
@@ -1,34 +0,0 @@
|
||||
/*
|
||||
* rdivide.h
|
||||
*
|
||||
* Code generation for function 'rdivide'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RDIVIDE_H__
|
||||
#define __RDIVIDE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_defines.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "attitudeKalmanfilter_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void rdivide(const real32_T x[3], real32_T y, real32_T z[3]);
|
||||
#endif
|
||||
/* End of code generation (rdivide.h) */
|
||||
@@ -1,139 +0,0 @@
|
||||
/*
|
||||
* rtGetInf.c
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* Abstract:
|
||||
* MATLAB for code generation function to initialize non-finite, Inf and MinusInf
|
||||
*/
|
||||
#include "rtGetInf.h"
|
||||
#define NumBitsPerChar 8U
|
||||
|
||||
/* Function: rtGetInf ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtInf needed by the generated code.
|
||||
* Inf is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real_T rtGetInf(void)
|
||||
{
|
||||
size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
|
||||
real_T inf = 0.0;
|
||||
if (bitsPerReal == 32U) {
|
||||
inf = rtGetInfF();
|
||||
} else {
|
||||
uint16_T one = 1U;
|
||||
enum {
|
||||
LittleEndian,
|
||||
BigEndian
|
||||
} machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
|
||||
switch (machByteOrder) {
|
||||
case LittleEndian:
|
||||
{
|
||||
union {
|
||||
LittleEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0x7FF00000U;
|
||||
tmpVal.bitVal.words.wordL = 0x00000000U;
|
||||
inf = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
|
||||
case BigEndian:
|
||||
{
|
||||
union {
|
||||
BigEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0x7FF00000U;
|
||||
tmpVal.bitVal.words.wordL = 0x00000000U;
|
||||
inf = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return inf;
|
||||
}
|
||||
|
||||
/* Function: rtGetInfF ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtInfF needed by the generated code.
|
||||
* Inf is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real32_T rtGetInfF(void)
|
||||
{
|
||||
IEEESingle infF;
|
||||
infF.wordL.wordLuint = 0x7F800000U;
|
||||
return infF.wordL.wordLreal;
|
||||
}
|
||||
|
||||
/* Function: rtGetMinusInf ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtMinusInf needed by the generated code.
|
||||
* Inf is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real_T rtGetMinusInf(void)
|
||||
{
|
||||
size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
|
||||
real_T minf = 0.0;
|
||||
if (bitsPerReal == 32U) {
|
||||
minf = rtGetMinusInfF();
|
||||
} else {
|
||||
uint16_T one = 1U;
|
||||
enum {
|
||||
LittleEndian,
|
||||
BigEndian
|
||||
} machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
|
||||
switch (machByteOrder) {
|
||||
case LittleEndian:
|
||||
{
|
||||
union {
|
||||
LittleEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0xFFF00000U;
|
||||
tmpVal.bitVal.words.wordL = 0x00000000U;
|
||||
minf = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
|
||||
case BigEndian:
|
||||
{
|
||||
union {
|
||||
BigEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0xFFF00000U;
|
||||
tmpVal.bitVal.words.wordL = 0x00000000U;
|
||||
minf = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return minf;
|
||||
}
|
||||
|
||||
/* Function: rtGetMinusInfF ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtMinusInfF needed by the generated code.
|
||||
* Inf is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real32_T rtGetMinusInfF(void)
|
||||
{
|
||||
IEEESingle minfF;
|
||||
minfF.wordL.wordLuint = 0xFF800000U;
|
||||
return minfF.wordL.wordLreal;
|
||||
}
|
||||
|
||||
/* End of code generation (rtGetInf.c) */
|
||||
@@ -1,23 +0,0 @@
|
||||
/*
|
||||
* rtGetInf.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RTGETINF_H__
|
||||
#define __RTGETINF_H__
|
||||
|
||||
#include <stddef.h>
|
||||
#include "rtwtypes.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
extern real_T rtGetInf(void);
|
||||
extern real32_T rtGetInfF(void);
|
||||
extern real_T rtGetMinusInf(void);
|
||||
extern real32_T rtGetMinusInfF(void);
|
||||
|
||||
#endif
|
||||
/* End of code generation (rtGetInf.h) */
|
||||
@@ -1,96 +0,0 @@
|
||||
/*
|
||||
* rtGetNaN.c
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* Abstract:
|
||||
* MATLAB for code generation function to initialize non-finite, NaN
|
||||
*/
|
||||
#include "rtGetNaN.h"
|
||||
#define NumBitsPerChar 8U
|
||||
|
||||
/* Function: rtGetNaN ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtNaN needed by the generated code.
|
||||
* NaN is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real_T rtGetNaN(void)
|
||||
{
|
||||
size_t bitsPerReal = sizeof(real_T) * (NumBitsPerChar);
|
||||
real_T nan = 0.0;
|
||||
if (bitsPerReal == 32U) {
|
||||
nan = rtGetNaNF();
|
||||
} else {
|
||||
uint16_T one = 1U;
|
||||
enum {
|
||||
LittleEndian,
|
||||
BigEndian
|
||||
} machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
|
||||
switch (machByteOrder) {
|
||||
case LittleEndian:
|
||||
{
|
||||
union {
|
||||
LittleEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0xFFF80000U;
|
||||
tmpVal.bitVal.words.wordL = 0x00000000U;
|
||||
nan = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
|
||||
case BigEndian:
|
||||
{
|
||||
union {
|
||||
BigEndianIEEEDouble bitVal;
|
||||
real_T fltVal;
|
||||
} tmpVal;
|
||||
|
||||
tmpVal.bitVal.words.wordH = 0x7FFFFFFFU;
|
||||
tmpVal.bitVal.words.wordL = 0xFFFFFFFFU;
|
||||
nan = tmpVal.fltVal;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return nan;
|
||||
}
|
||||
|
||||
/* Function: rtGetNaNF ==================================================
|
||||
* Abstract:
|
||||
* Initialize rtNaNF needed by the generated code.
|
||||
* NaN is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
real32_T rtGetNaNF(void)
|
||||
{
|
||||
IEEESingle nanF = { { 0 } };
|
||||
uint16_T one = 1U;
|
||||
enum {
|
||||
LittleEndian,
|
||||
BigEndian
|
||||
} machByteOrder = (*((uint8_T *) &one) == 1U) ? LittleEndian : BigEndian;
|
||||
switch (machByteOrder) {
|
||||
case LittleEndian:
|
||||
{
|
||||
nanF.wordL.wordLuint = 0xFFC00000U;
|
||||
break;
|
||||
}
|
||||
|
||||
case BigEndian:
|
||||
{
|
||||
nanF.wordL.wordLuint = 0x7FFFFFFFU;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return nanF.wordL.wordLreal;
|
||||
}
|
||||
|
||||
/* End of code generation (rtGetNaN.c) */
|
||||
@@ -1,21 +0,0 @@
|
||||
/*
|
||||
* rtGetNaN.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RTGETNAN_H__
|
||||
#define __RTGETNAN_H__
|
||||
|
||||
#include <stddef.h>
|
||||
#include "rtwtypes.h"
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
extern real_T rtGetNaN(void);
|
||||
extern real32_T rtGetNaNF(void);
|
||||
|
||||
#endif
|
||||
/* End of code generation (rtGetNaN.h) */
|
||||
@@ -1,24 +0,0 @@
|
||||
/*
|
||||
* rt_defines.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RT_DEFINES_H__
|
||||
#define __RT_DEFINES_H__
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#define RT_PI 3.14159265358979323846
|
||||
#define RT_PIF 3.1415927F
|
||||
#define RT_LN_10 2.30258509299404568402
|
||||
#define RT_LN_10F 2.3025851F
|
||||
#define RT_LOG10E 0.43429448190325182765
|
||||
#define RT_LOG10EF 0.43429449F
|
||||
#define RT_E 2.7182818284590452354
|
||||
#define RT_EF 2.7182817F
|
||||
#endif
|
||||
/* End of code generation (rt_defines.h) */
|
||||
@@ -1,87 +0,0 @@
|
||||
/*
|
||||
* rt_nonfinite.c
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/*
|
||||
* Abstract:
|
||||
* MATLAB for code generation function to initialize non-finites,
|
||||
* (Inf, NaN and -Inf).
|
||||
*/
|
||||
#include "rt_nonfinite.h"
|
||||
#include "rtGetNaN.h"
|
||||
#include "rtGetInf.h"
|
||||
|
||||
real_T rtInf;
|
||||
real_T rtMinusInf;
|
||||
real_T rtNaN;
|
||||
real32_T rtInfF;
|
||||
real32_T rtMinusInfF;
|
||||
real32_T rtNaNF;
|
||||
|
||||
/* Function: rt_InitInfAndNaN ==================================================
|
||||
* Abstract:
|
||||
* Initialize the rtInf, rtMinusInf, and rtNaN needed by the
|
||||
* generated code. NaN is initialized as non-signaling. Assumes IEEE.
|
||||
*/
|
||||
void rt_InitInfAndNaN(size_t realSize)
|
||||
{
|
||||
(void) (realSize);
|
||||
rtNaN = rtGetNaN();
|
||||
rtNaNF = rtGetNaNF();
|
||||
rtInf = rtGetInf();
|
||||
rtInfF = rtGetInfF();
|
||||
rtMinusInf = rtGetMinusInf();
|
||||
rtMinusInfF = rtGetMinusInfF();
|
||||
}
|
||||
|
||||
/* Function: rtIsInf ==================================================
|
||||
* Abstract:
|
||||
* Test if value is infinite
|
||||
*/
|
||||
boolean_T rtIsInf(real_T value)
|
||||
{
|
||||
return ((value==rtInf || value==rtMinusInf) ? 1U : 0U);
|
||||
}
|
||||
|
||||
/* Function: rtIsInfF =================================================
|
||||
* Abstract:
|
||||
* Test if single-precision value is infinite
|
||||
*/
|
||||
boolean_T rtIsInfF(real32_T value)
|
||||
{
|
||||
return(((value)==rtInfF || (value)==rtMinusInfF) ? 1U : 0U);
|
||||
}
|
||||
|
||||
/* Function: rtIsNaN ==================================================
|
||||
* Abstract:
|
||||
* Test if value is not a number
|
||||
*/
|
||||
boolean_T rtIsNaN(real_T value)
|
||||
{
|
||||
#if defined(_MSC_VER) && (_MSC_VER <= 1200)
|
||||
return _isnan(value)? TRUE:FALSE;
|
||||
#else
|
||||
return (value!=value)? 1U:0U;
|
||||
#endif
|
||||
}
|
||||
|
||||
/* Function: rtIsNaNF =================================================
|
||||
* Abstract:
|
||||
* Test if single-precision value is not a number
|
||||
*/
|
||||
boolean_T rtIsNaNF(real32_T value)
|
||||
{
|
||||
#if defined(_MSC_VER) && (_MSC_VER <= 1200)
|
||||
return _isnan((real_T)value)? true:false;
|
||||
#else
|
||||
return (value!=value)? 1U:0U;
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
/* End of code generation (rt_nonfinite.c) */
|
||||
@@ -1,53 +0,0 @@
|
||||
/*
|
||||
* rt_nonfinite.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RT_NONFINITE_H__
|
||||
#define __RT_NONFINITE_H__
|
||||
|
||||
#if defined(_MSC_VER) && (_MSC_VER <= 1200)
|
||||
#include <float.h>
|
||||
#endif
|
||||
#include <stddef.h>
|
||||
#include "rtwtypes.h"
|
||||
|
||||
extern real_T rtInf;
|
||||
extern real_T rtMinusInf;
|
||||
extern real_T rtNaN;
|
||||
extern real32_T rtInfF;
|
||||
extern real32_T rtMinusInfF;
|
||||
extern real32_T rtNaNF;
|
||||
extern void rt_InitInfAndNaN(size_t realSize);
|
||||
extern boolean_T rtIsInf(real_T value);
|
||||
extern boolean_T rtIsInfF(real32_T value);
|
||||
extern boolean_T rtIsNaN(real_T value);
|
||||
extern boolean_T rtIsNaNF(real32_T value);
|
||||
|
||||
typedef struct {
|
||||
struct {
|
||||
uint32_T wordH;
|
||||
uint32_T wordL;
|
||||
} words;
|
||||
} BigEndianIEEEDouble;
|
||||
|
||||
typedef struct {
|
||||
struct {
|
||||
uint32_T wordL;
|
||||
uint32_T wordH;
|
||||
} words;
|
||||
} LittleEndianIEEEDouble;
|
||||
|
||||
typedef struct {
|
||||
union {
|
||||
real32_T wordLreal;
|
||||
uint32_T wordLuint;
|
||||
} wordL;
|
||||
} IEEESingle;
|
||||
|
||||
#endif
|
||||
/* End of code generation (rt_nonfinite.h) */
|
||||
Executable → Regular
+160
-159
@@ -1,159 +1,160 @@
|
||||
/*
|
||||
* rtwtypes.h
|
||||
*
|
||||
* Code generation for function 'attitudeKalmanfilter'
|
||||
*
|
||||
* C source code generated on: Sat Jan 19 15:25:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RTWTYPES_H__
|
||||
#define __RTWTYPES_H__
|
||||
#ifndef TRUE
|
||||
# define TRUE (1U)
|
||||
#endif
|
||||
#ifndef FALSE
|
||||
# define FALSE (0U)
|
||||
#endif
|
||||
#ifndef __TMWTYPES__
|
||||
#define __TMWTYPES__
|
||||
|
||||
#include <limits.h>
|
||||
|
||||
/*=======================================================================*
|
||||
* Target hardware information
|
||||
* Device type: Generic->MATLAB Host Computer
|
||||
* Number of bits: char: 8 short: 16 int: 32
|
||||
* long: 32 native word size: 32
|
||||
* Byte ordering: LittleEndian
|
||||
* Signed integer division rounds to: Zero
|
||||
* Shift right on a signed integer as arithmetic shift: on
|
||||
*=======================================================================*/
|
||||
|
||||
/*=======================================================================*
|
||||
* Fixed width word size data types: *
|
||||
* int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
|
||||
* uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
|
||||
* real32_T, real64_T - 32 and 64 bit floating point numbers *
|
||||
*=======================================================================*/
|
||||
|
||||
typedef signed char int8_T;
|
||||
typedef unsigned char uint8_T;
|
||||
typedef short int16_T;
|
||||
typedef unsigned short uint16_T;
|
||||
typedef int int32_T;
|
||||
typedef unsigned int uint32_T;
|
||||
typedef float real32_T;
|
||||
typedef double real64_T;
|
||||
|
||||
/*===========================================================================*
|
||||
* Generic type definitions: real_T, time_T, boolean_T, int_T, uint_T, *
|
||||
* ulong_T, char_T and byte_T. *
|
||||
*===========================================================================*/
|
||||
|
||||
typedef double real_T;
|
||||
typedef double time_T;
|
||||
typedef unsigned char boolean_T;
|
||||
typedef int int_T;
|
||||
typedef unsigned int uint_T;
|
||||
typedef unsigned long ulong_T;
|
||||
typedef char char_T;
|
||||
typedef char_T byte_T;
|
||||
|
||||
/*===========================================================================*
|
||||
* Complex number type definitions *
|
||||
*===========================================================================*/
|
||||
#define CREAL_T
|
||||
typedef struct {
|
||||
real32_T re;
|
||||
real32_T im;
|
||||
} creal32_T;
|
||||
|
||||
typedef struct {
|
||||
real64_T re;
|
||||
real64_T im;
|
||||
} creal64_T;
|
||||
|
||||
typedef struct {
|
||||
real_T re;
|
||||
real_T im;
|
||||
} creal_T;
|
||||
|
||||
typedef struct {
|
||||
int8_T re;
|
||||
int8_T im;
|
||||
} cint8_T;
|
||||
|
||||
typedef struct {
|
||||
uint8_T re;
|
||||
uint8_T im;
|
||||
} cuint8_T;
|
||||
|
||||
typedef struct {
|
||||
int16_T re;
|
||||
int16_T im;
|
||||
} cint16_T;
|
||||
|
||||
typedef struct {
|
||||
uint16_T re;
|
||||
uint16_T im;
|
||||
} cuint16_T;
|
||||
|
||||
typedef struct {
|
||||
int32_T re;
|
||||
int32_T im;
|
||||
} cint32_T;
|
||||
|
||||
typedef struct {
|
||||
uint32_T re;
|
||||
uint32_T im;
|
||||
} cuint32_T;
|
||||
|
||||
|
||||
/*=======================================================================*
|
||||
* Min and Max: *
|
||||
* int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
|
||||
* uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
|
||||
*=======================================================================*/
|
||||
|
||||
#define MAX_int8_T ((int8_T)(127))
|
||||
#define MIN_int8_T ((int8_T)(-128))
|
||||
#define MAX_uint8_T ((uint8_T)(255))
|
||||
#define MIN_uint8_T ((uint8_T)(0))
|
||||
#define MAX_int16_T ((int16_T)(32767))
|
||||
#define MIN_int16_T ((int16_T)(-32768))
|
||||
#define MAX_uint16_T ((uint16_T)(65535))
|
||||
#define MIN_uint16_T ((uint16_T)(0))
|
||||
#define MAX_int32_T ((int32_T)(2147483647))
|
||||
#define MIN_int32_T ((int32_T)(-2147483647-1))
|
||||
#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU))
|
||||
#define MIN_uint32_T ((uint32_T)(0))
|
||||
|
||||
/* Logical type definitions */
|
||||
#if !defined(__cplusplus) && !defined(__true_false_are_keywords)
|
||||
# ifndef false
|
||||
# define false (0U)
|
||||
# endif
|
||||
# ifndef true
|
||||
# define true (1U)
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* MATLAB for code generation assumes the code is compiled on a target using a 2's compliment representation
|
||||
* for signed integer values.
|
||||
*/
|
||||
#if ((SCHAR_MIN + 1) != -SCHAR_MAX)
|
||||
#error "This code must be compiled using a 2's complement representation for signed integer values"
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Maximum length of a MATLAB identifier (function/variable)
|
||||
* including the null-termination character. Referenced by
|
||||
* rt_logging.c and rt_matrx.c.
|
||||
*/
|
||||
#define TMW_NAME_LENGTH_MAX 64
|
||||
|
||||
#endif
|
||||
#endif
|
||||
/* End of code generation (rtwtypes.h) */
|
||||
/*
|
||||
* rtwtypes.h
|
||||
*
|
||||
* Code generation for function 'AttitudeEKF'
|
||||
*
|
||||
* C source code generated on: Thu Aug 21 11:17:28 2014
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __RTWTYPES_H__
|
||||
#define __RTWTYPES_H__
|
||||
#ifndef TRUE
|
||||
# define TRUE (1U)
|
||||
#endif
|
||||
#ifndef FALSE
|
||||
# define FALSE (0U)
|
||||
#endif
|
||||
#ifndef __TMWTYPES__
|
||||
#define __TMWTYPES__
|
||||
|
||||
#include <limits.h>
|
||||
|
||||
/*=======================================================================*
|
||||
* Target hardware information
|
||||
* Device type: ARM Compatible->ARM Cortex
|
||||
* Number of bits: char: 8 short: 16 int: 32
|
||||
* long: 32
|
||||
* native word size: 32
|
||||
* Byte ordering: LittleEndian
|
||||
* Signed integer division rounds to: Undefined
|
||||
* Shift right on a signed integer as arithmetic shift: on
|
||||
*=======================================================================*/
|
||||
|
||||
/*=======================================================================*
|
||||
* Fixed width word size data types: *
|
||||
* int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
|
||||
* uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
|
||||
* real32_T, real64_T - 32 and 64 bit floating point numbers *
|
||||
*=======================================================================*/
|
||||
|
||||
typedef signed char int8_T;
|
||||
typedef unsigned char uint8_T;
|
||||
typedef short int16_T;
|
||||
typedef unsigned short uint16_T;
|
||||
typedef int int32_T;
|
||||
typedef unsigned int uint32_T;
|
||||
typedef float real32_T;
|
||||
typedef double real64_T;
|
||||
|
||||
/*===========================================================================*
|
||||
* Generic type definitions: real_T, time_T, boolean_T, int_T, uint_T, *
|
||||
* ulong_T, char_T and byte_T. *
|
||||
*===========================================================================*/
|
||||
|
||||
typedef double real_T;
|
||||
typedef double time_T;
|
||||
typedef unsigned char boolean_T;
|
||||
typedef int int_T;
|
||||
typedef unsigned int uint_T;
|
||||
typedef unsigned long ulong_T;
|
||||
typedef char char_T;
|
||||
typedef char_T byte_T;
|
||||
|
||||
/*===========================================================================*
|
||||
* Complex number type definitions *
|
||||
*===========================================================================*/
|
||||
#define CREAL_T
|
||||
typedef struct {
|
||||
real32_T re;
|
||||
real32_T im;
|
||||
} creal32_T;
|
||||
|
||||
typedef struct {
|
||||
real64_T re;
|
||||
real64_T im;
|
||||
} creal64_T;
|
||||
|
||||
typedef struct {
|
||||
real_T re;
|
||||
real_T im;
|
||||
} creal_T;
|
||||
|
||||
typedef struct {
|
||||
int8_T re;
|
||||
int8_T im;
|
||||
} cint8_T;
|
||||
|
||||
typedef struct {
|
||||
uint8_T re;
|
||||
uint8_T im;
|
||||
} cuint8_T;
|
||||
|
||||
typedef struct {
|
||||
int16_T re;
|
||||
int16_T im;
|
||||
} cint16_T;
|
||||
|
||||
typedef struct {
|
||||
uint16_T re;
|
||||
uint16_T im;
|
||||
} cuint16_T;
|
||||
|
||||
typedef struct {
|
||||
int32_T re;
|
||||
int32_T im;
|
||||
} cint32_T;
|
||||
|
||||
typedef struct {
|
||||
uint32_T re;
|
||||
uint32_T im;
|
||||
} cuint32_T;
|
||||
|
||||
|
||||
/*=======================================================================*
|
||||
* Min and Max: *
|
||||
* int8_T, int16_T, int32_T - signed 8, 16, or 32 bit integers *
|
||||
* uint8_T, uint16_T, uint32_T - unsigned 8, 16, or 32 bit integers *
|
||||
*=======================================================================*/
|
||||
|
||||
#define MAX_int8_T ((int8_T)(127))
|
||||
#define MIN_int8_T ((int8_T)(-128))
|
||||
#define MAX_uint8_T ((uint8_T)(255))
|
||||
#define MIN_uint8_T ((uint8_T)(0))
|
||||
#define MAX_int16_T ((int16_T)(32767))
|
||||
#define MIN_int16_T ((int16_T)(-32768))
|
||||
#define MAX_uint16_T ((uint16_T)(65535))
|
||||
#define MIN_uint16_T ((uint16_T)(0))
|
||||
#define MAX_int32_T ((int32_T)(2147483647))
|
||||
#define MIN_int32_T ((int32_T)(-2147483647-1))
|
||||
#define MAX_uint32_T ((uint32_T)(0xFFFFFFFFU))
|
||||
#define MIN_uint32_T ((uint32_T)(0))
|
||||
|
||||
/* Logical type definitions */
|
||||
#if !defined(__cplusplus) && !defined(__true_false_are_keywords)
|
||||
# ifndef false
|
||||
# define false (0U)
|
||||
# endif
|
||||
# ifndef true
|
||||
# define true (1U)
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/*
|
||||
* MATLAB for code generation assumes the code is compiled on a target using a 2's compliment representation
|
||||
* for signed integer values.
|
||||
*/
|
||||
#if ((SCHAR_MIN + 1) != -SCHAR_MAX)
|
||||
#error "This code must be compiled using a 2's complement representation for signed integer values"
|
||||
#endif
|
||||
|
||||
/*
|
||||
* Maximum length of a MATLAB identifier (function/variable)
|
||||
* including the null-termination character. Referenced by
|
||||
* rt_logging.c and rt_matrx.c.
|
||||
*/
|
||||
#define TMW_NAME_LENGTH_MAX 64
|
||||
|
||||
#endif
|
||||
#endif
|
||||
/* End of code generation (rtwtypes.h) */
|
||||
|
||||
@@ -39,16 +39,6 @@ MODULE_COMMAND = attitude_estimator_ekf
|
||||
|
||||
SRCS = attitude_estimator_ekf_main.cpp \
|
||||
attitude_estimator_ekf_params.c \
|
||||
codegen/eye.c \
|
||||
codegen/attitudeKalmanfilter.c \
|
||||
codegen/mrdivide.c \
|
||||
codegen/rdivide.c \
|
||||
codegen/attitudeKalmanfilter_initialize.c \
|
||||
codegen/attitudeKalmanfilter_terminate.c \
|
||||
codegen/rt_nonfinite.c \
|
||||
codegen/rtGetInf.c \
|
||||
codegen/rtGetNaN.c \
|
||||
codegen/norm.c \
|
||||
codegen/cross.c
|
||||
codegen/AttitudeEKF.c
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -223,7 +223,7 @@ BottleDrop::start()
|
||||
_main_task = task_spawn_cmd("bottle_drop",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 15,
|
||||
2048,
|
||||
1500,
|
||||
(main_t)&BottleDrop::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
||||
@@ -41,3 +41,5 @@ SRCS = bottle_drop.cpp \
|
||||
bottle_drop_params.c
|
||||
|
||||
MAXOPTIMIZATION = -Os
|
||||
|
||||
MODULE_STACKSIZE = 1200
|
||||
|
||||
@@ -263,7 +263,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
|
||||
const int samples_num = 2500;
|
||||
float accel_ref[6][3];
|
||||
bool data_collected[6] = { false, false, false, false, false, false };
|
||||
const char *orientation_strs[6] = { "front", "back", "left", "right", "top", "bottom" };
|
||||
const char *orientation_strs[6] = { "back", "front", "left", "right", "up", "down" };
|
||||
|
||||
int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined));
|
||||
|
||||
@@ -294,12 +294,12 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
|
||||
|
||||
/* inform user which axes are still needed */
|
||||
mavlink_log_info(mavlink_fd, "pending: %s%s%s%s%s%s",
|
||||
(!data_collected[0]) ? "front " : "",
|
||||
(!data_collected[1]) ? "back " : "",
|
||||
(!data_collected[5]) ? "down " : "",
|
||||
(!data_collected[0]) ? "back " : "",
|
||||
(!data_collected[1]) ? "front " : "",
|
||||
(!data_collected[2]) ? "left " : "",
|
||||
(!data_collected[3]) ? "right " : "",
|
||||
(!data_collected[4]) ? "up " : "",
|
||||
(!data_collected[5]) ? "down " : "");
|
||||
(!data_collected[4]) ? "up " : "");
|
||||
|
||||
/* allow user enough time to read the message */
|
||||
sleep(3);
|
||||
|
||||
@@ -310,12 +310,16 @@ int commander_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "arm")) {
|
||||
arm_disarm(true, mavlink_fd, "command line");
|
||||
int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0);
|
||||
arm_disarm(true, mavlink_fd_local, "command line");
|
||||
close(mavlink_fd_local);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
if (!strcmp(argv[1], "disarm")) {
|
||||
arm_disarm(false, mavlink_fd, "command line");
|
||||
int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0);
|
||||
arm_disarm(false, mavlink_fd_local, "command line");
|
||||
close(mavlink_fd_local);
|
||||
exit(0);
|
||||
}
|
||||
|
||||
@@ -1544,7 +1548,7 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
} else {
|
||||
if (status.rc_signal_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "RC signal regained");
|
||||
mavlink_log_critical(mavlink_fd, "RC SIGNAL REGAINED after %llums",(hrt_absolute_time()-status.rc_signal_lost_timestamp)/1000);
|
||||
status_changed = true;
|
||||
}
|
||||
}
|
||||
@@ -1645,8 +1649,9 @@ int commander_thread_main(int argc, char *argv[])
|
||||
|
||||
} else {
|
||||
if (!status.rc_signal_lost) {
|
||||
mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST");
|
||||
mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST (at t=%llums)",hrt_absolute_time()/1000);
|
||||
status.rc_signal_lost = true;
|
||||
status.rc_signal_lost_timestamp=sp_man.timestamp;
|
||||
status_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -706,7 +706,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd)
|
||||
}
|
||||
|
||||
if (fabsf(airspeed.indicated_airspeed_m_s > 6.0f)) {
|
||||
mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION MISSING");
|
||||
mavlink_log_critical(mavlink_fd, "AIRSPEED WARNING: WIND OR CALIBRATION ISSUE");
|
||||
// XXX do not make this fatal yet
|
||||
}
|
||||
}
|
||||
|
||||
@@ -629,9 +629,6 @@ task_main(int argc, char *argv[])
|
||||
{
|
||||
work_q_item_t *work;
|
||||
|
||||
/* inform about start */
|
||||
warnx("Initializing..");
|
||||
|
||||
/* Initialize global variables */
|
||||
g_key_offsets[0] = 0;
|
||||
|
||||
@@ -694,16 +691,15 @@ task_main(int argc, char *argv[])
|
||||
if (sys_restart_val == DM_INIT_REASON_POWER_ON) {
|
||||
warnx("Power on restart");
|
||||
_restart(DM_INIT_REASON_POWER_ON);
|
||||
}
|
||||
else if (sys_restart_val == DM_INIT_REASON_IN_FLIGHT) {
|
||||
} else if (sys_restart_val == DM_INIT_REASON_IN_FLIGHT) {
|
||||
warnx("In flight restart");
|
||||
_restart(DM_INIT_REASON_IN_FLIGHT);
|
||||
}
|
||||
else
|
||||
} else {
|
||||
warnx("Unknown restart");
|
||||
}
|
||||
else
|
||||
}
|
||||
} else {
|
||||
warnx("Unknown restart");
|
||||
}
|
||||
|
||||
/* We use two file descriptors, one for the caller context and one for the worker thread */
|
||||
/* They are actually the same but we need to some way to reject caller request while the */
|
||||
|
||||
@@ -1560,7 +1560,7 @@ FixedwingEstimator::start()
|
||||
_estimator_task = task_spawn_cmd("ekf_att_pos_estimator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_MAX - 40,
|
||||
5000,
|
||||
7500,
|
||||
(main_t)&FixedwingEstimator::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
||||
@@ -751,14 +751,32 @@ FixedwingAttitudeControl::task_main()
|
||||
* - manual control is disabled (another app may send the setpoint, but it should
|
||||
* for sure not be set from the remote control values)
|
||||
*/
|
||||
if (_vcontrol_mode.flag_control_velocity_enabled ||
|
||||
_vcontrol_mode.flag_control_position_enabled ||
|
||||
if (_vcontrol_mode.flag_control_auto_enabled ||
|
||||
!_vcontrol_mode.flag_control_manual_enabled) {
|
||||
/* read in attitude setpoint from attitude setpoint uorb topic */
|
||||
roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad;
|
||||
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
|
||||
throttle_sp = _att_sp.thrust;
|
||||
|
||||
/* reset integrals where needed */
|
||||
if (_att_sp.roll_reset_integral) {
|
||||
_roll_ctrl.reset_integrator();
|
||||
}
|
||||
if (_att_sp.pitch_reset_integral) {
|
||||
_pitch_ctrl.reset_integrator();
|
||||
}
|
||||
if (_att_sp.yaw_reset_integral) {
|
||||
_yaw_ctrl.reset_integrator();
|
||||
}
|
||||
} else if (_vcontrol_mode.flag_control_velocity_enabled) {
|
||||
/*
|
||||
* Velocity should be controlled and manual is enabled.
|
||||
*/
|
||||
roll_sp = (_manual.y * _parameters.man_roll_max - _parameters.trim_roll)
|
||||
+ _parameters.rollsp_offset_rad;
|
||||
pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad;
|
||||
throttle_sp = _att_sp.thrust;
|
||||
|
||||
/* reset integrals where needed */
|
||||
if (_att_sp.roll_reset_integral) {
|
||||
_roll_ctrl.reset_integrator();
|
||||
|
||||
@@ -163,6 +163,9 @@ private:
|
||||
|
||||
perf_counter_t _loop_perf; /**< loop performance counter */
|
||||
|
||||
float _hold_alt; /**< hold altitude for velocity mode */
|
||||
hrt_abstime _control_position_last_called; /**<last call of control_position */
|
||||
|
||||
/* land states */
|
||||
bool land_noreturn_horizontal;
|
||||
bool land_noreturn_vertical;
|
||||
@@ -198,6 +201,8 @@ private:
|
||||
TECS _tecs;
|
||||
fwPosctrl::mTecs _mTecs;
|
||||
bool _was_pos_control_mode;
|
||||
bool _was_velocity_control_mode;
|
||||
bool _was_alt_control_mode;
|
||||
|
||||
struct {
|
||||
float l1_period;
|
||||
@@ -316,6 +321,11 @@ private:
|
||||
*/
|
||||
void vehicle_status_poll();
|
||||
|
||||
/**
|
||||
* Check for manual setpoint updates.
|
||||
*/
|
||||
bool vehicle_manual_control_setpoint_poll();
|
||||
|
||||
/**
|
||||
* Check for airspeed updates.
|
||||
*/
|
||||
@@ -439,6 +449,9 @@ FixedwingPositionControl::FixedwingPositionControl() :
|
||||
/* performance counters */
|
||||
_loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")),
|
||||
|
||||
_hold_alt(0.0f),
|
||||
_control_position_last_called(0),
|
||||
|
||||
land_noreturn_horizontal(false),
|
||||
land_noreturn_vertical(false),
|
||||
land_stayonground(false),
|
||||
@@ -692,6 +705,22 @@ FixedwingPositionControl::vehicle_airspeed_poll()
|
||||
return airspeed_updated;
|
||||
}
|
||||
|
||||
bool
|
||||
FixedwingPositionControl::vehicle_manual_control_setpoint_poll()
|
||||
{
|
||||
bool manual_updated;
|
||||
|
||||
/* Check if manual setpoint has changed */
|
||||
orb_check(_manual_control_sub, &manual_updated);
|
||||
|
||||
if (manual_updated) {
|
||||
orb_copy(ORB_ID(manual_control_setpoint), _manual_control_sub, &_manual);
|
||||
}
|
||||
|
||||
return manual_updated;
|
||||
}
|
||||
|
||||
|
||||
void
|
||||
FixedwingPositionControl::vehicle_attitude_poll()
|
||||
{
|
||||
@@ -852,6 +881,12 @@ bool
|
||||
FixedwingPositionControl::control_position(const math::Vector<2> ¤t_position, const math::Vector<3> &ground_speed,
|
||||
const struct position_setpoint_triplet_s &pos_sp_triplet)
|
||||
{
|
||||
float dt = FLT_MIN; // Using non zero value to a avoid division by zero
|
||||
if (_control_position_last_called > 0) {
|
||||
dt = (float)hrt_elapsed_time(&_control_position_last_called) * 1e-6f;
|
||||
}
|
||||
_control_position_last_called = hrt_absolute_time();
|
||||
|
||||
bool setpoint = true;
|
||||
|
||||
math::Vector<2> ground_speed_2d = {ground_speed(0), ground_speed(1)};
|
||||
@@ -888,6 +923,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
}
|
||||
|
||||
_was_pos_control_mode = true;
|
||||
_was_velocity_control_mode = false;
|
||||
|
||||
/* reset hold altitude */
|
||||
_hold_alt = _global_pos.alt;
|
||||
|
||||
/* get circle mode */
|
||||
bool was_circle_mode = _l1_control.circle_mode();
|
||||
@@ -1209,12 +1248,59 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi
|
||||
_att_sp.roll_reset_integral = true;
|
||||
}
|
||||
|
||||
} else {
|
||||
} else if (_control_mode.flag_control_velocity_enabled) {
|
||||
const float deadBand = (60.0f/1000.0f);
|
||||
const float factor = 1.0f - deadBand;
|
||||
if (!_was_velocity_control_mode) {
|
||||
_hold_alt = _global_pos.alt;
|
||||
_was_alt_control_mode = false;
|
||||
}
|
||||
_was_velocity_control_mode = true;
|
||||
_was_pos_control_mode = false;
|
||||
// Get demanded airspeed
|
||||
float altctrl_airspeed = _parameters.airspeed_min +
|
||||
(_parameters.airspeed_max - _parameters.airspeed_min) *
|
||||
_manual.z;
|
||||
|
||||
// Get demanded vertical velocity from pitch control
|
||||
float pitch = 0.0f;
|
||||
if (_manual.x > deadBand) {
|
||||
pitch = (_manual.x - deadBand) / factor;
|
||||
} else if (_manual.x < - deadBand) {
|
||||
pitch = (_manual.x + deadBand) / factor;
|
||||
}
|
||||
if (pitch > 0.0f) {
|
||||
_hold_alt -= (_parameters.max_climb_rate * dt) * pitch;
|
||||
_was_alt_control_mode = false;
|
||||
} else if (pitch < 0.0f) {
|
||||
_hold_alt -= (_parameters.max_sink_rate * dt) * pitch;
|
||||
_was_alt_control_mode = false;
|
||||
} else if (!_was_alt_control_mode) {
|
||||
_hold_alt = _global_pos.alt;
|
||||
_was_alt_control_mode = true;
|
||||
}
|
||||
tecs_update_pitch_throttle(_hold_alt,
|
||||
altctrl_airspeed,
|
||||
eas2tas,
|
||||
math::radians(_parameters.pitch_limit_min),
|
||||
math::radians(_parameters.pitch_limit_max),
|
||||
_parameters.throttle_min,
|
||||
_parameters.throttle_max,
|
||||
_parameters.throttle_cruise,
|
||||
false,
|
||||
math::radians(_parameters.pitch_limit_min),
|
||||
_global_pos.alt,
|
||||
ground_speed,
|
||||
TECS_MODE_NORMAL);
|
||||
} else {
|
||||
_was_velocity_control_mode = false;
|
||||
_was_pos_control_mode = false;
|
||||
|
||||
/** MANUAL FLIGHT **/
|
||||
|
||||
/* reset hold altitude */
|
||||
_hold_alt = _global_pos.alt;
|
||||
|
||||
/* no flight mode applies, do not publish an attitude setpoint */
|
||||
setpoint = false;
|
||||
|
||||
@@ -1350,6 +1436,7 @@ FixedwingPositionControl::task_main()
|
||||
vehicle_setpoint_poll();
|
||||
vehicle_sensor_combined_poll();
|
||||
vehicle_airspeed_poll();
|
||||
vehicle_manual_control_setpoint_poll();
|
||||
// vehicle_baro_poll();
|
||||
|
||||
math::Vector<3> ground_speed(_global_pos.vel_n, _global_pos.vel_e, _global_pos.vel_d);
|
||||
|
||||
@@ -1405,7 +1405,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
|
||||
configure_stream("ATTITUDE_TARGET", 3.0f);
|
||||
configure_stream("DISTANCE_SENSOR", 0.5f);
|
||||
configure_stream("OPTICAL_FLOW", 5.0f);
|
||||
configure_stream("OPTICAL_FLOW_RAD", 5.0f);
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_ONBOARD:
|
||||
@@ -1636,7 +1636,7 @@ Mavlink::start(int argc, char *argv[])
|
||||
task_spawn_cmd(buf,
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT,
|
||||
2900,
|
||||
2800,
|
||||
(main_t)&Mavlink::start_helper,
|
||||
(const char **)argv);
|
||||
|
||||
|
||||
@@ -810,9 +810,6 @@ private:
|
||||
MavlinkOrbSubscription *_airspeed_sub;
|
||||
uint64_t _airspeed_time;
|
||||
|
||||
MavlinkOrbSubscription *_sensor_combined_sub;
|
||||
uint64_t _sensor_combined_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &);
|
||||
MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &);
|
||||
@@ -828,9 +825,7 @@ protected:
|
||||
_act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_controls_0))),
|
||||
_act_time(0),
|
||||
_airspeed_sub(_mavlink->add_orb_subscription(ORB_ID(airspeed))),
|
||||
_airspeed_time(0),
|
||||
_sensor_combined_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_combined))),
|
||||
_sensor_combined_time(0)
|
||||
_airspeed_time(0)
|
||||
{}
|
||||
|
||||
void send(const hrt_abstime t)
|
||||
@@ -840,14 +835,12 @@ protected:
|
||||
struct actuator_armed_s armed;
|
||||
struct actuator_controls_s act;
|
||||
struct airspeed_s airspeed;
|
||||
struct sensor_combined_s sensor_combined;
|
||||
|
||||
bool updated = _att_sub->update(&_att_time, &att);
|
||||
updated |= _pos_sub->update(&_pos_time, &pos);
|
||||
updated |= _armed_sub->update(&_armed_time, &armed);
|
||||
updated |= _act_sub->update(&_act_time, &act);
|
||||
updated |= _airspeed_sub->update(&_airspeed_time, &airspeed);
|
||||
updated |= _sensor_combined_sub->update(&_sensor_combined_time, &sensor_combined);
|
||||
|
||||
if (updated) {
|
||||
mavlink_vfr_hud_t msg;
|
||||
@@ -856,7 +849,7 @@ protected:
|
||||
msg.groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e);
|
||||
msg.heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F;
|
||||
msg.throttle = armed.armed ? act.control[3] * 100.0f : 0.0f;
|
||||
msg.alt = sensor_combined.baro_alt_meter;
|
||||
msg.alt = pos.alt;
|
||||
msg.climb = -pos.vel_d;
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_VFR_HUD, &msg);
|
||||
@@ -1834,33 +1827,32 @@ protected:
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
class MavlinkStreamOpticalFlow : public MavlinkStream
|
||||
class MavlinkStreamOpticalFlowRad : public MavlinkStream
|
||||
{
|
||||
public:
|
||||
const char *get_name() const
|
||||
{
|
||||
return MavlinkStreamOpticalFlow::get_name_static();
|
||||
return MavlinkStreamOpticalFlowRad::get_name_static();
|
||||
}
|
||||
|
||||
static const char *get_name_static()
|
||||
{
|
||||
return "OPTICAL_FLOW";
|
||||
return "OPTICAL_FLOW_RAD";
|
||||
}
|
||||
|
||||
uint8_t get_id()
|
||||
{
|
||||
return MAVLINK_MSG_ID_OPTICAL_FLOW;
|
||||
return MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
|
||||
}
|
||||
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink)
|
||||
{
|
||||
return new MavlinkStreamOpticalFlow(mavlink);
|
||||
return new MavlinkStreamOpticalFlowRad(mavlink);
|
||||
}
|
||||
|
||||
unsigned get_size()
|
||||
{
|
||||
return _flow_sub->is_published() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
||||
return _flow_sub->is_published() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0;
|
||||
}
|
||||
|
||||
private:
|
||||
@@ -1868,11 +1860,11 @@ private:
|
||||
uint64_t _flow_time;
|
||||
|
||||
/* do not allow top copying this class */
|
||||
MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &);
|
||||
MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &);
|
||||
MavlinkStreamOpticalFlowRad(MavlinkStreamOpticalFlowRad &);
|
||||
MavlinkStreamOpticalFlowRad& operator = (const MavlinkStreamOpticalFlowRad &);
|
||||
|
||||
protected:
|
||||
explicit MavlinkStreamOpticalFlow(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
explicit MavlinkStreamOpticalFlowRad(Mavlink *mavlink) : MavlinkStream(mavlink),
|
||||
_flow_sub(_mavlink->add_orb_subscription(ORB_ID(optical_flow))),
|
||||
_flow_time(0)
|
||||
{}
|
||||
@@ -1882,18 +1874,23 @@ protected:
|
||||
struct optical_flow_s flow;
|
||||
|
||||
if (_flow_sub->update(&_flow_time, &flow)) {
|
||||
mavlink_optical_flow_t msg;
|
||||
mavlink_optical_flow_rad_t msg;
|
||||
|
||||
msg.time_usec = flow.timestamp;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.flow_x = flow.flow_raw_x;
|
||||
msg.flow_y = flow.flow_raw_y;
|
||||
msg.flow_comp_m_x = flow.flow_comp_x_m;
|
||||
msg.flow_comp_m_y = flow.flow_comp_y_m;
|
||||
msg.integrated_x = flow.pixel_flow_x_integral;
|
||||
msg.integrated_y = flow.pixel_flow_y_integral;
|
||||
msg.integrated_xgyro = flow.gyro_x_rate_integral;
|
||||
msg.integrated_ygyro = flow.gyro_y_rate_integral;
|
||||
msg.integrated_zgyro = flow.gyro_z_rate_integral;
|
||||
msg.distance = flow.ground_distance_m;
|
||||
msg.quality = flow.quality;
|
||||
msg.ground_distance = flow.ground_distance_m;
|
||||
msg.integration_time_us = flow.integration_timespan;
|
||||
msg.sensor_id = flow.sensor_id;
|
||||
msg.time_delta_distance_us = flow.time_since_last_sonar_update;
|
||||
msg.temperature = flow.gyro_temperature;
|
||||
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_OPTICAL_FLOW, &msg);
|
||||
_mavlink->send_message(MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, &msg);
|
||||
}
|
||||
}
|
||||
};
|
||||
@@ -2199,7 +2196,7 @@ StreamListItem *streams_list[] = {
|
||||
new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamOpticalFlowRad::new_instance, &MavlinkStreamOpticalFlowRad::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static),
|
||||
new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static),
|
||||
|
||||
@@ -144,8 +144,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
|
||||
handle_message_command_int(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_OPTICAL_FLOW:
|
||||
handle_message_optical_flow(msg);
|
||||
case MAVLINK_MSG_ID_OPTICAL_FLOW_RAD:
|
||||
handle_message_optical_flow_rad(msg);
|
||||
break;
|
||||
|
||||
case MAVLINK_MSG_ID_SET_MODE:
|
||||
@@ -352,24 +352,27 @@ MavlinkReceiver::handle_message_command_int(mavlink_message_t *msg)
|
||||
}
|
||||
|
||||
void
|
||||
MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
|
||||
MavlinkReceiver::handle_message_optical_flow_rad(mavlink_message_t *msg)
|
||||
{
|
||||
/* optical flow */
|
||||
mavlink_optical_flow_t flow;
|
||||
mavlink_msg_optical_flow_decode(msg, &flow);
|
||||
mavlink_optical_flow_rad_t flow;
|
||||
mavlink_msg_optical_flow_rad_decode(msg, &flow);
|
||||
|
||||
struct optical_flow_s f;
|
||||
memset(&f, 0, sizeof(f));
|
||||
|
||||
f.timestamp = hrt_absolute_time();
|
||||
f.flow_timestamp = flow.time_usec;
|
||||
f.flow_raw_x = flow.flow_x;
|
||||
f.flow_raw_y = flow.flow_y;
|
||||
f.flow_comp_x_m = flow.flow_comp_m_x;
|
||||
f.flow_comp_y_m = flow.flow_comp_m_y;
|
||||
f.ground_distance_m = flow.ground_distance;
|
||||
f.timestamp = flow.time_usec;
|
||||
f.integration_timespan = flow.integration_time_us;
|
||||
f.pixel_flow_x_integral = flow.integrated_x;
|
||||
f.pixel_flow_y_integral = flow.integrated_y;
|
||||
f.gyro_x_rate_integral = flow.integrated_xgyro;
|
||||
f.gyro_y_rate_integral = flow.integrated_ygyro;
|
||||
f.gyro_z_rate_integral = flow.integrated_zgyro;
|
||||
f.time_since_last_sonar_update = flow.time_delta_distance_us;
|
||||
f.ground_distance_m = flow.distance;
|
||||
f.quality = flow.quality;
|
||||
f.sensor_id = flow.sensor_id;
|
||||
f.gyro_temperature = flow.temperature;
|
||||
|
||||
if (_flow_pub < 0) {
|
||||
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||
@@ -389,13 +392,18 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
|
||||
struct optical_flow_s f;
|
||||
memset(&f, 0, sizeof(f));
|
||||
|
||||
f.timestamp = hrt_absolute_time();
|
||||
f.flow_timestamp = flow.time_usec;
|
||||
f.flow_raw_x = flow.integrated_x;
|
||||
f.flow_raw_y = flow.integrated_y;
|
||||
f.timestamp = hrt_absolute_time(); // XXX we rely on the system time for now and not flow.time_usec;
|
||||
f.integration_timespan = flow.integration_time_us;
|
||||
f.pixel_flow_x_integral = flow.integrated_x;
|
||||
f.pixel_flow_y_integral = flow.integrated_y;
|
||||
f.gyro_x_rate_integral = flow.integrated_xgyro;
|
||||
f.gyro_y_rate_integral = flow.integrated_ygyro;
|
||||
f.gyro_z_rate_integral = flow.integrated_zgyro;
|
||||
f.time_since_last_sonar_update = flow.time_delta_distance_us;
|
||||
f.ground_distance_m = flow.distance;
|
||||
f.quality = flow.quality;
|
||||
f.sensor_id = flow.sensor_id;
|
||||
f.gyro_temperature = flow.temperature;
|
||||
|
||||
if (_flow_pub < 0) {
|
||||
_flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
|
||||
@@ -538,12 +546,16 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
||||
offboard_control_sp.ignore &= ~(1 << i);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << i));
|
||||
}
|
||||
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAW);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 10)) <<
|
||||
OFB_IGN_BIT_YAW;
|
||||
if (set_position_target_local_ned.type_mask & (1 << 10)) {
|
||||
offboard_control_sp.ignore |= (1 << OFB_IGN_BIT_YAW);
|
||||
}
|
||||
|
||||
offboard_control_sp.ignore &= ~(1 << OFB_IGN_BIT_YAWRATE);
|
||||
offboard_control_sp.ignore |= (set_position_target_local_ned.type_mask & (1 << 11)) <<
|
||||
OFB_IGN_BIT_YAWRATE;
|
||||
if (set_position_target_local_ned.type_mask & (1 << 11)) {
|
||||
offboard_control_sp.ignore |= (1 << OFB_IGN_BIT_YAWRATE);
|
||||
}
|
||||
|
||||
offboard_control_sp.timestamp = hrt_absolute_time();
|
||||
|
||||
|
||||
@@ -112,7 +112,7 @@ private:
|
||||
void handle_message(mavlink_message_t *msg);
|
||||
void handle_message_command_long(mavlink_message_t *msg);
|
||||
void handle_message_command_int(mavlink_message_t *msg);
|
||||
void handle_message_optical_flow(mavlink_message_t *msg);
|
||||
void handle_message_optical_flow_rad(mavlink_message_t *msg);
|
||||
void handle_message_hil_optical_flow(mavlink_message_t *msg);
|
||||
void handle_message_set_mode(mavlink_message_t *msg);
|
||||
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
|
||||
|
||||
@@ -721,8 +721,6 @@ MulticopterAttitudeControl::task_main_trampoline(int argc, char *argv[])
|
||||
void
|
||||
MulticopterAttitudeControl::task_main()
|
||||
{
|
||||
warnx("started");
|
||||
fflush(stdout);
|
||||
|
||||
/*
|
||||
* do subscriptions
|
||||
|
||||
@@ -535,7 +535,7 @@ MulticopterPositionControl::reset_pos_sp()
|
||||
- _params.vel_ff(0) * _sp_move_rate(0)) / _params.pos_p(0);
|
||||
_pos_sp(1) = _pos(1) + (_vel(1) - _att_sp.R_body[1][2] * _att_sp.thrust / _params.vel_p(1)
|
||||
- _params.vel_ff(1) * _sp_move_rate(1)) / _params.pos_p(1);
|
||||
mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1));
|
||||
mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %d, %d", (int)_pos_sp(0), (int)_pos_sp(1));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -545,7 +545,7 @@ MulticopterPositionControl::reset_alt_sp()
|
||||
if (_reset_alt_sp) {
|
||||
_reset_alt_sp = false;
|
||||
_pos_sp(2) = _pos(2) + (_vel(2) - _params.vel_ff(2) * _sp_move_rate(2)) / _params.pos_p(2);
|
||||
mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2));
|
||||
mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %d", -(int)_pos_sp(2));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -857,10 +857,8 @@ MulticopterPositionControl::control_auto(float dt)
|
||||
void
|
||||
MulticopterPositionControl::task_main()
|
||||
{
|
||||
warnx("started");
|
||||
|
||||
_mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
mavlink_log_info(_mavlink_fd, "[mpc] started");
|
||||
|
||||
/*
|
||||
* do subscriptions
|
||||
|
||||
@@ -205,6 +205,7 @@ private:
|
||||
|
||||
bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */
|
||||
bool _pos_sp_triplet_updated; /**< flags if position SP triplet needs to be published */
|
||||
bool _pos_sp_triplet_published_invalid_once; /**< flags if position SP triplet has been published once to UORB */
|
||||
|
||||
control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */
|
||||
control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */
|
||||
|
||||
@@ -137,6 +137,7 @@ Navigator::Navigator() :
|
||||
_gpsFailure(this, "GPSF"),
|
||||
_can_loiter_at_sp(false),
|
||||
_pos_sp_triplet_updated(false),
|
||||
_pos_sp_triplet_published_invalid_once(false),
|
||||
_param_loiter_radius(this, "LOITER_RAD"),
|
||||
_param_acceptance_radius(this, "ACC_RAD"),
|
||||
_param_datalinkloss_obc(this, "DLL_OBC"),
|
||||
@@ -427,12 +428,15 @@ Navigator::task_main()
|
||||
_can_loiter_at_sp = false;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_MISSION:
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
_navigation_mode = &_mission;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LOITER:
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
_navigation_mode = &_loiter;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RCRECOVER:
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
if (_param_rcloss_obc.get() != 0) {
|
||||
_navigation_mode = &_rcLoss;
|
||||
} else {
|
||||
@@ -440,11 +444,13 @@ Navigator::task_main()
|
||||
}
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTL:
|
||||
_navigation_mode = &_rtl;
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
_navigation_mode = &_rtl;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_RTGS:
|
||||
/* Use complex data link loss mode only when enabled via param
|
||||
* otherwise use rtl */
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
if (_param_datalinkloss_obc.get() != 0) {
|
||||
_navigation_mode = &_dataLinkLoss;
|
||||
} else {
|
||||
@@ -452,9 +458,11 @@ Navigator::task_main()
|
||||
}
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LANDENGFAIL:
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
_navigation_mode = &_engineFailure;
|
||||
break;
|
||||
case NAVIGATION_STATE_AUTO_LANDGPSFAIL:
|
||||
_pos_sp_triplet_published_invalid_once = false;
|
||||
_navigation_mode = &_gpsFailure;
|
||||
break;
|
||||
default:
|
||||
@@ -468,9 +476,9 @@ Navigator::task_main()
|
||||
_navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]);
|
||||
}
|
||||
|
||||
/* if nothing is running, set position setpoint triplet invalid */
|
||||
if (_navigation_mode == nullptr) {
|
||||
// TODO publish empty sp only once
|
||||
/* if nothing is running, set position setpoint triplet invalid once */
|
||||
if (_navigation_mode == nullptr && !_pos_sp_triplet_published_invalid_once) {
|
||||
_pos_sp_triplet_published_invalid_once = true;
|
||||
_pos_sp_triplet.previous.valid = false;
|
||||
_pos_sp_triplet.current.valid = false;
|
||||
_pos_sp_triplet.next.valid = false;
|
||||
@@ -499,7 +507,7 @@ Navigator::start()
|
||||
_navigator_task = task_spawn_cmd("navigator",
|
||||
SCHED_DEFAULT,
|
||||
SCHED_PRIORITY_DEFAULT + 20,
|
||||
2000,
|
||||
1800,
|
||||
(main_t)&Navigator::task_main_trampoline,
|
||||
nullptr);
|
||||
|
||||
|
||||
@@ -161,7 +161,7 @@ int position_estimator_inav_main(int argc, char *argv[])
|
||||
thread_should_exit = true;
|
||||
|
||||
} else {
|
||||
warnx("app not started");
|
||||
warnx("not started");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
@@ -169,10 +169,10 @@ int position_estimator_inav_main(int argc, char *argv[])
|
||||
|
||||
if (!strcmp(argv[1], "status")) {
|
||||
if (thread_running) {
|
||||
warnx("app is running");
|
||||
warnx("is running");
|
||||
|
||||
} else {
|
||||
warnx("app not started");
|
||||
warnx("not started");
|
||||
}
|
||||
|
||||
exit(0);
|
||||
@@ -210,10 +210,8 @@ static void write_debug_log(const char *msg, float dt, float x_est[2], float y_e
|
||||
****************************************************************************/
|
||||
int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
{
|
||||
warnx("started");
|
||||
int mavlink_fd;
|
||||
mavlink_fd = open(MAVLINK_LOG_DEVICE, 0);
|
||||
mavlink_log_info(mavlink_fd, "[inav] started");
|
||||
|
||||
float x_est[2] = { 0.0f, 0.0f }; // pos, vel
|
||||
float y_est[2] = { 0.0f, 0.0f }; // pos, vel
|
||||
@@ -298,7 +296,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
float w_flow = 0.0f;
|
||||
|
||||
float sonar_prev = 0.0f;
|
||||
hrt_abstime flow_prev = 0; // time of last flow measurement
|
||||
//hrt_abstime flow_prev = 0; // time of last flow measurement
|
||||
hrt_abstime sonar_time = 0; // time of last sonar measurement (not filtered)
|
||||
hrt_abstime sonar_valid_time = 0; // time of last sonar measurement used for correction (filtered)
|
||||
|
||||
@@ -389,8 +387,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
} else {
|
||||
wait_baro = false;
|
||||
baro_offset /= (float) baro_init_cnt;
|
||||
warnx("baro offs: %.2f", (double)baro_offset);
|
||||
mavlink_log_info(mavlink_fd, "[inav] baro offs: %.2f", (double)baro_offset);
|
||||
warnx("baro offs: %d", (int)baro_offset);
|
||||
mavlink_log_info(mavlink_fd, "[inav] baro offs: %d", (int)baro_offset);
|
||||
local_pos.z_valid = true;
|
||||
local_pos.v_z_valid = true;
|
||||
}
|
||||
@@ -491,8 +489,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
orb_copy(ORB_ID(optical_flow), optical_flow_sub, &flow);
|
||||
|
||||
/* calculate time from previous update */
|
||||
float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
|
||||
flow_prev = flow.flow_timestamp;
|
||||
// float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
|
||||
// flow_prev = flow.flow_timestamp;
|
||||
|
||||
if ((flow.ground_distance_m > 0.31f) &&
|
||||
(flow.ground_distance_m < 4.0f) &&
|
||||
@@ -520,7 +518,7 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
sonar_valid_time = t;
|
||||
sonar_valid = true;
|
||||
local_pos.surface_bottom_timestamp = t;
|
||||
mavlink_log_info(mavlink_fd, "[inav] new surface level: %.2f", (double)surface_offset);
|
||||
mavlink_log_info(mavlink_fd, "[inav] new surface level: %d", (int)surface_offset);
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -550,8 +548,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
|
||||
/* convert raw flow to angular flow (rad/s) */
|
||||
float flow_ang[2];
|
||||
flow_ang[0] = flow.flow_raw_x * params.flow_k / 1000.0f / flow_dt;
|
||||
flow_ang[1] = flow.flow_raw_y * params.flow_k / 1000.0f / flow_dt;
|
||||
//todo check direction of x und y axis
|
||||
flow_ang[0] = flow.pixel_flow_x_integral/(float)flow.integration_timespan*1000000.0f;//flow.flow_raw_x * params.flow_k / 1000.0f / flow_dt;
|
||||
flow_ang[1] = flow.pixel_flow_y_integral/(float)flow.integration_timespan*1000000.0f;//flow.flow_raw_y * params.flow_k / 1000.0f / flow_dt;
|
||||
/* flow measurements vector */
|
||||
float flow_m[3];
|
||||
flow_m[0] = -flow_ang[0] * flow_dist;
|
||||
@@ -721,8 +720,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
|
||||
|
||||
/* initialize projection */
|
||||
map_projection_init(&ref, lat, lon);
|
||||
warnx("init ref: lat=%.7f, lon=%.7f, alt=%.2f", (double)lat, (double)lon, (double)alt);
|
||||
mavlink_log_info(mavlink_fd, "[inav] init ref: %.7f, %.7f, %.2f", (double)lat, (double)lon, (double)alt);
|
||||
// XXX replace this print
|
||||
warnx("init ref: lat=%.7f, lon=%.7f, alt=%8.4f", (double)lat, (double)lon, (double)alt);
|
||||
mavlink_log_info(mavlink_fd, "[inav] init ref: %.7f, %.7f, %8.4f", (double)lat, (double)lon, (double)alt);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -353,12 +353,16 @@ static unsigned mixer_text_length = 0;
|
||||
int
|
||||
mixer_handle_text(const void *buffer, size_t length)
|
||||
{
|
||||
/* do not allow a mixer change while safety off */
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)) {
|
||||
/* do not allow a mixer change while safety off and FMU armed */
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) &&
|
||||
(r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
|
||||
return 1;
|
||||
}
|
||||
|
||||
/* abort if we're in the mixer */
|
||||
/* disable mixing, will be enabled once load is complete */
|
||||
r_status_flags &= ~(PX4IO_P_STATUS_FLAGS_MIXER_OK);
|
||||
|
||||
/* abort if we're in the mixer - the caller is expected to retry */
|
||||
if (in_mixer) {
|
||||
return 1;
|
||||
}
|
||||
@@ -367,17 +371,16 @@ mixer_handle_text(const void *buffer, size_t length)
|
||||
|
||||
isr_debug(2, "mix txt %u", length);
|
||||
|
||||
if (length < sizeof(px4io_mixdata))
|
||||
if (length < sizeof(px4io_mixdata)) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
unsigned text_length = length - sizeof(px4io_mixdata);
|
||||
unsigned text_length = length - sizeof(px4io_mixdata);
|
||||
|
||||
switch (msg->action) {
|
||||
case F2I_MIXER_ACTION_RESET:
|
||||
isr_debug(2, "reset");
|
||||
|
||||
/* FIRST mark the mixer as invalid */
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
/* THEN actually delete it */
|
||||
mixer_group.reset();
|
||||
mixer_text_length = 0;
|
||||
@@ -386,9 +389,6 @@ mixer_handle_text(const void *buffer, size_t length)
|
||||
case F2I_MIXER_ACTION_APPEND:
|
||||
isr_debug(2, "append %d", length);
|
||||
|
||||
/* disable mixing during the update */
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
|
||||
/* check for overflow - this would be really fatal */
|
||||
if ((mixer_text_length + text_length + 1) > sizeof(mixer_text)) {
|
||||
r_status_flags &= ~PX4IO_P_STATUS_FLAGS_MIXER_OK;
|
||||
|
||||
@@ -407,11 +407,11 @@ registers_set(uint8_t page, uint8_t offset, const uint16_t *values, unsigned num
|
||||
|
||||
/* handle text going to the mixer parser */
|
||||
case PX4IO_PAGE_MIXERLOAD:
|
||||
if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
|
||||
return mixer_handle_text(values, num_values * sizeof(*values));
|
||||
}
|
||||
break;
|
||||
/* do not change the mixer if FMU is armed and IO's safety is off
|
||||
* this state defines an active system. This check is done in the
|
||||
* text handling function.
|
||||
*/
|
||||
return mixer_handle_text(values, num_values * sizeof(*values));
|
||||
|
||||
default:
|
||||
/* avoid offset wrap */
|
||||
@@ -583,8 +583,7 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
||||
break;
|
||||
|
||||
case PX4IO_P_SETUP_REBOOT_BL:
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
|
||||
// don't allow reboot while armed
|
||||
break;
|
||||
}
|
||||
@@ -630,10 +629,9 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
|
||||
case PX4IO_PAGE_RC_CONFIG: {
|
||||
|
||||
/**
|
||||
* do not allow a RC config change while outputs armed
|
||||
* do not allow a RC config change while safety is off
|
||||
*/
|
||||
if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
|
||||
(r_status_flags & PX4IO_P_STATUS_FLAGS_OUTPUTS_ARMED)) {
|
||||
if (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
||||
@@ -496,6 +496,8 @@ static void *logwriter_thread(void *arg)
|
||||
/* set name */
|
||||
prctl(PR_SET_NAME, "sdlog2_writer", 0);
|
||||
|
||||
perf_counter_t perf_write = perf_alloc(PC_ELAPSED, "sd write");
|
||||
|
||||
int log_fd = open_log_file();
|
||||
|
||||
if (log_fd < 0) {
|
||||
@@ -553,7 +555,9 @@ static void *logwriter_thread(void *arg)
|
||||
n = available;
|
||||
}
|
||||
|
||||
perf_begin(perf_write);
|
||||
n = write(log_fd, read_ptr, n);
|
||||
perf_end(perf_write);
|
||||
|
||||
should_wait = (n == available) && !is_part;
|
||||
|
||||
@@ -586,6 +590,9 @@ static void *logwriter_thread(void *arg)
|
||||
fsync(log_fd);
|
||||
close(log_fd);
|
||||
|
||||
/* free performance counter */
|
||||
perf_free(perf_write);
|
||||
|
||||
return NULL;
|
||||
}
|
||||
|
||||
@@ -1511,11 +1518,14 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
/* --- FLOW --- */
|
||||
if (copy_if_updated(ORB_ID(optical_flow), subs.flow_sub, &buf.flow)) {
|
||||
log_msg.msg_type = LOG_FLOW_MSG;
|
||||
log_msg.body.log_FLOW.flow_raw_x = buf.flow.flow_raw_x;
|
||||
log_msg.body.log_FLOW.flow_raw_y = buf.flow.flow_raw_y;
|
||||
log_msg.body.log_FLOW.flow_comp_x = buf.flow.flow_comp_x_m;
|
||||
log_msg.body.log_FLOW.flow_comp_y = buf.flow.flow_comp_y_m;
|
||||
log_msg.body.log_FLOW.distance = buf.flow.ground_distance_m;
|
||||
log_msg.body.log_FLOW.ground_distance_m = buf.flow.ground_distance_m;
|
||||
log_msg.body.log_FLOW.gyro_temperature = buf.flow.gyro_temperature;
|
||||
log_msg.body.log_FLOW.gyro_x_rate_integral = buf.flow.gyro_x_rate_integral;
|
||||
log_msg.body.log_FLOW.gyro_y_rate_integral = buf.flow.gyro_y_rate_integral;
|
||||
log_msg.body.log_FLOW.gyro_z_rate_integral = buf.flow.gyro_z_rate_integral;
|
||||
log_msg.body.log_FLOW.integration_timespan = buf.flow.integration_timespan;
|
||||
log_msg.body.log_FLOW.pixel_flow_x_integral = buf.flow.pixel_flow_x_integral;
|
||||
log_msg.body.log_FLOW.pixel_flow_y_integral = buf.flow.pixel_flow_y_integral;
|
||||
log_msg.body.log_FLOW.quality = buf.flow.quality;
|
||||
log_msg.body.log_FLOW.sensor_id = buf.flow.sensor_id;
|
||||
LOGBUFFER_WRITE_AND_COUNT(FLOW);
|
||||
|
||||
@@ -200,13 +200,19 @@ struct log_ARSP_s {
|
||||
/* --- FLOW - OPTICAL FLOW --- */
|
||||
#define LOG_FLOW_MSG 15
|
||||
struct log_FLOW_s {
|
||||
int16_t flow_raw_x;
|
||||
int16_t flow_raw_y;
|
||||
float flow_comp_x;
|
||||
float flow_comp_y;
|
||||
float distance;
|
||||
uint8_t quality;
|
||||
uint64_t timestamp;
|
||||
uint8_t sensor_id;
|
||||
float pixel_flow_x_integral;
|
||||
float pixel_flow_y_integral;
|
||||
float gyro_x_rate_integral;
|
||||
float gyro_y_rate_integral;
|
||||
float gyro_z_rate_integral;
|
||||
float ground_distance_m;
|
||||
uint32_t integration_timespan;
|
||||
uint32_t time_since_last_sonar_update;
|
||||
uint16_t frame_count_since_last_readout;
|
||||
int16_t gyro_temperature;
|
||||
uint8_t quality;
|
||||
};
|
||||
|
||||
/* --- GPOS - GLOBAL POSITION ESTIMATE --- */
|
||||
|
||||
@@ -41,6 +41,7 @@
|
||||
#define SYSTEMLIB_H_
|
||||
#include <float.h>
|
||||
#include <stdint.h>
|
||||
#include <sched.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
|
||||
@@ -46,6 +46,7 @@
|
||||
#include "topics/vehicle_attitude_setpoint.h"
|
||||
#include "topics/vehicle_rates_setpoint.h"
|
||||
#include "topics/actuator_outputs.h"
|
||||
#include "topics/actuator_direct.h"
|
||||
#include "topics/encoders.h"
|
||||
#include "topics/tecs_status.h"
|
||||
|
||||
@@ -76,6 +77,7 @@ template class __EXPORT Publication<vehicle_global_velocity_setpoint_s>;
|
||||
template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
|
||||
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
|
||||
template class __EXPORT Publication<actuator_outputs_s>;
|
||||
template class __EXPORT Publication<actuator_direct_s>;
|
||||
template class __EXPORT Publication<encoders_s>;
|
||||
template class __EXPORT Publication<tecs_status_s>;
|
||||
|
||||
|
||||
@@ -192,6 +192,9 @@ ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
|
||||
ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
|
||||
ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
|
||||
|
||||
#include "topics/actuator_direct.h"
|
||||
ORB_DEFINE(actuator_direct, struct actuator_direct_s);
|
||||
|
||||
#include "topics/multirotor_motor_limits.h"
|
||||
ORB_DEFINE(multirotor_motor_limits, struct multirotor_motor_limits_s);
|
||||
|
||||
|
||||
+28
-29
@@ -1,8 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2008-2013 PX4 Development Team. All rights reserved.
|
||||
* Author: Samuel Zihlmann <samuezih@ee.ethz.ch>
|
||||
* Lorenz Meier <lm@inf.ethz.ch>
|
||||
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -33,38 +31,39 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* @file flow_speed_control_params.h
|
||||
*
|
||||
* Parameters for speed controller
|
||||
/**
|
||||
* @file actuator_direct.h
|
||||
*
|
||||
* Actuator direct values.
|
||||
*
|
||||
* Values published to this topic are the direct actuator values which
|
||||
* should be passed to actuators, bypassing mixing
|
||||
*/
|
||||
|
||||
#include <systemlib/param/param.h>
|
||||
#ifndef TOPIC_ACTUATOR_DIRECT_H
|
||||
#define TOPIC_ACTUATOR_DIRECT_H
|
||||
|
||||
struct flow_speed_control_params {
|
||||
float speed_p;
|
||||
float limit_pitch;
|
||||
float limit_roll;
|
||||
float trim_roll;
|
||||
float trim_pitch;
|
||||
};
|
||||
#include <stdint.h>
|
||||
#include "../uORB.h"
|
||||
|
||||
struct flow_speed_control_param_handles {
|
||||
param_t speed_p;
|
||||
param_t limit_pitch;
|
||||
param_t limit_roll;
|
||||
param_t trim_roll;
|
||||
param_t trim_pitch;
|
||||
#define NUM_ACTUATORS_DIRECT 16
|
||||
|
||||
/**
|
||||
* @addtogroup topics
|
||||
* @{
|
||||
*/
|
||||
|
||||
struct actuator_direct_s {
|
||||
uint64_t timestamp; /**< timestamp in us since system boot */
|
||||
float values[NUM_ACTUATORS_DIRECT]; /**< actuator values, from -1 to 1 */
|
||||
unsigned nvalues; /**< number of valid values */
|
||||
};
|
||||
|
||||
/**
|
||||
* Initialize all parameter handles and values
|
||||
*
|
||||
* @}
|
||||
*/
|
||||
int parameters_init(struct flow_speed_control_param_handles *h);
|
||||
|
||||
/**
|
||||
* Update all parameters
|
||||
*
|
||||
*/
|
||||
int parameters_update(const struct flow_speed_control_param_handles *h, struct flow_speed_control_params *p);
|
||||
/* actuator direct ORB */
|
||||
ORB_DECLARE(actuator_direct);
|
||||
|
||||
#endif // TOPIC_ACTUATOR_DIRECT_H
|
||||
@@ -61,7 +61,7 @@ struct home_position_s
|
||||
|
||||
double lat; /**< Latitude in degrees */
|
||||
double lon; /**< Longitude in degrees */
|
||||
float alt; /**< Altitude in meters */
|
||||
float alt; /**< Altitude in meters (AMSL) */
|
||||
|
||||
float x; /**< X coordinate in meters */
|
||||
float y; /**< Y coordinate in meters */
|
||||
|
||||
@@ -83,7 +83,7 @@ struct mission_item_s {
|
||||
bool altitude_is_relative; /**< true if altitude is relative from start point */
|
||||
double lat; /**< latitude in degrees */
|
||||
double lon; /**< longitude in degrees */
|
||||
float altitude; /**< altitude in meters */
|
||||
float altitude; /**< altitude in meters (AMSL) */
|
||||
float yaw; /**< in radians NED -PI..+PI, NAN means don't change yaw */
|
||||
float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
|
||||
int8_t loiter_direction; /**< 1: positive / clockwise, -1, negative. */
|
||||
|
||||
@@ -55,16 +55,22 @@
|
||||
*/
|
||||
struct optical_flow_s {
|
||||
|
||||
uint64_t timestamp; /**< in microseconds since system start */
|
||||
|
||||
uint64_t flow_timestamp; /**< timestamp from flow sensor */
|
||||
int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
|
||||
int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
|
||||
float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
|
||||
float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
|
||||
float ground_distance_m; /**< Altitude / distance to ground in meters */
|
||||
uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
|
||||
uint64_t timestamp; /**< in microseconds since system start */
|
||||
uint8_t sensor_id; /**< id of the sensor emitting the flow value */
|
||||
float pixel_flow_x_integral; /**< accumulated optical flow in radians around x axis */
|
||||
float pixel_flow_y_integral; /**< accumulated optical flow in radians around y axis */
|
||||
float gyro_x_rate_integral; /**< accumulated gyro value in radians around x axis */
|
||||
float gyro_y_rate_integral; /**< accumulated gyro value in radians around y axis */
|
||||
float gyro_z_rate_integral; /**< accumulated gyro value in radians around z axis */
|
||||
float ground_distance_m; /**< Altitude / distance to ground in meters */
|
||||
uint32_t integration_timespan; /**<accumulation timespan in microseconds */
|
||||
uint32_t time_since_last_sonar_update;/**< time since last sonar update in microseconds */
|
||||
uint16_t frame_count_since_last_readout;/**< number of accumulated frames in timespan */
|
||||
int16_t gyro_temperature;/**< Temperature * 100 in centi-degrees Celsius */
|
||||
uint8_t quality; /**< Average of quality of accumulated frames, 0: bad quality, 255: maximum quality */
|
||||
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -65,7 +65,7 @@ enum VEHICLE_CMD {
|
||||
VEHICLE_CMD_NAV_TAKEOFF = 22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
|
||||
VEHICLE_CMD_NAV_ROI = 80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
|
||||
VEHICLE_CMD_NAV_PATHPLANNING = 81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
|
||||
VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, WGS84) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, WGS84) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_GUIDED_LIMITS=90, /* set limits for external control |timeout - maximum time (in seconds) that external controller will be allowed to control vehicle. 0 means no timeout| absolute altitude min (in meters, AMSL) - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit| absolute altitude max (in meters)- if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit| horizontal move limit (in meters, AMSL) - if vehicle moves more than this distance from it's location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal altitude limit| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_GUIDED_MASTER=91, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_GUIDED_ENABLE=92, /* hand control over to an external controller |On / Off (> 0.5f on)| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
VEHICLE_CMD_NAV_LAST = 95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
|
||||
|
||||
@@ -79,7 +79,7 @@ struct vehicle_gps_position_s {
|
||||
bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */
|
||||
|
||||
uint64_t timestamp_time; /**< Timestamp for time information */
|
||||
uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
|
||||
uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module. It might be unavailable right after cold start, indicated by a value of 0 */
|
||||
|
||||
uint8_t satellites_used; /**< Number of satellites used */
|
||||
};
|
||||
|
||||
@@ -201,6 +201,7 @@ struct vehicle_status_s {
|
||||
|
||||
bool rc_signal_found_once;
|
||||
bool rc_signal_lost; /**< true if RC reception lost */
|
||||
uint64_t rc_signal_lost_timestamp; /**< Time at which the RC reception was lost */
|
||||
bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
|
||||
bool rc_input_blocked; /**< set if RC input should be ignored */
|
||||
|
||||
|
||||
@@ -76,7 +76,9 @@ int UavcanEscController::init()
|
||||
|
||||
void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
||||
{
|
||||
if ((outputs == nullptr) || (num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize)) {
|
||||
if ((outputs == nullptr) ||
|
||||
(num_outputs > uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize) ||
|
||||
(num_outputs > CONNECTED_ESC_MAX)) {
|
||||
perf_count(_perfcnt_invalid_input);
|
||||
return;
|
||||
}
|
||||
@@ -101,10 +103,15 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs)
|
||||
for (unsigned i = 0; i < num_outputs; i++) {
|
||||
if (_armed_mask & MOTOR_BIT(i)) {
|
||||
float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max;
|
||||
if (scaled < 1.0F) {
|
||||
scaled = 1.0F; // Since we're armed, we don't want to stop it completely
|
||||
}
|
||||
|
||||
// trim negative values back to 0. Previously
|
||||
// we set this to 0.1, which meant motors kept
|
||||
// spinning when armed, but that should be a
|
||||
// policy decision for a specific vehicle
|
||||
// type, as it is not appropriate for all
|
||||
// types of vehicles (eg. fixed wing).
|
||||
if (scaled < 0.0F) {
|
||||
scaled = 0.0F;
|
||||
}
|
||||
if (scaled > cmd_max) {
|
||||
scaled = cmd_max;
|
||||
perf_count(_perfcnt_scaling_error);
|
||||
|
||||
@@ -91,11 +91,7 @@ void UavcanBarometerBridge::air_data_sub_cb(const uavcan::ReceivedDataStructure<
|
||||
{
|
||||
auto report = ::baro_report();
|
||||
|
||||
report.timestamp = msg.getUtcTimestamp().toUSec();
|
||||
if (report.timestamp == 0) {
|
||||
report.timestamp = msg.getMonotonicTimestamp().toUSec();
|
||||
}
|
||||
|
||||
report.timestamp = msg.getMonotonicTimestamp().toUSec();
|
||||
report.temperature = msg.static_temperature;
|
||||
report.pressure = msg.static_pressure / 100.0F; // Convert to millibar
|
||||
|
||||
|
||||
@@ -92,7 +92,7 @@ void UavcanGnssBridge::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavca
|
||||
|
||||
auto report = ::vehicle_gps_position_s();
|
||||
|
||||
report.timestamp_position = hrt_absolute_time();
|
||||
report.timestamp_position = msg.getMonotonicTimestamp().toUSec();
|
||||
report.lat = msg.latitude_deg_1e8 / 10;
|
||||
report.lon = msg.longitude_deg_1e8 / 10;
|
||||
report.alt = msg.height_msl_mm;
|
||||
|
||||
@@ -43,8 +43,6 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
|
||||
#include <uORB/uORB.h>
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
|
||||
|
||||
@@ -37,6 +37,8 @@
|
||||
|
||||
#include "mag.hpp"
|
||||
|
||||
#include <systemlib/err.h>
|
||||
|
||||
static const orb_id_t MAG_TOPICS[3] = {
|
||||
ORB_ID(sensor_mag0),
|
||||
ORB_ID(sensor_mag1),
|
||||
@@ -71,9 +73,36 @@ int UavcanMagnetometerBridge::init()
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t UavcanMagnetometerBridge::read(struct file *filp, char *buffer, size_t buflen)
|
||||
{
|
||||
static uint64_t last_read = 0;
|
||||
struct mag_report *mag_buf = reinterpret_cast<struct mag_report *>(buffer);
|
||||
|
||||
/* buffer must be large enough */
|
||||
unsigned count = buflen / sizeof(struct mag_report);
|
||||
if (count < 1) {
|
||||
return -ENOSPC;
|
||||
}
|
||||
|
||||
if (last_read < _report.timestamp) {
|
||||
/* copy report */
|
||||
lock();
|
||||
*mag_buf = _report;
|
||||
last_read = _report.timestamp;
|
||||
unlock();
|
||||
return sizeof(struct mag_report);
|
||||
} else {
|
||||
/* no new data available, warn caller */
|
||||
return -EAGAIN;
|
||||
}
|
||||
}
|
||||
|
||||
int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long arg)
|
||||
{
|
||||
switch (cmd) {
|
||||
case SENSORIOCSQUEUEDEPTH: {
|
||||
return OK; // Pretend that this stuff is supported to keep APM happy
|
||||
}
|
||||
case MAGIOCSSCALE: {
|
||||
std::memcpy(&_scale, reinterpret_cast<const void*>(arg), sizeof(_scale));
|
||||
return 0;
|
||||
@@ -86,7 +115,7 @@ int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long ar
|
||||
return 0; // Nothing to do
|
||||
}
|
||||
case MAGIOCGEXTERNAL: {
|
||||
return 0; // We don't want anyone to transform the coordinate frame, so we declare it onboard
|
||||
return 1; // declare it external rise it's priority and to allow for correct orientation compensation
|
||||
}
|
||||
case MAGIOCSSAMPLERATE: {
|
||||
return 0; // Pretend that this stuff is supported to keep the sensor app happy
|
||||
@@ -108,18 +137,14 @@ int UavcanMagnetometerBridge::ioctl(struct file *filp, int cmd, unsigned long ar
|
||||
|
||||
void UavcanMagnetometerBridge::mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg)
|
||||
{
|
||||
auto report = ::mag_report();
|
||||
lock();
|
||||
_report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything
|
||||
_report.timestamp = msg.getMonotonicTimestamp().toUSec();
|
||||
|
||||
report.range_ga = 1.3F; // Arbitrary number, doesn't really mean anything
|
||||
_report.x = (msg.magnetic_field[0] - _scale.x_offset) * _scale.x_scale;
|
||||
_report.y = (msg.magnetic_field[1] - _scale.y_offset) * _scale.y_scale;
|
||||
_report.z = (msg.magnetic_field[2] - _scale.z_offset) * _scale.z_scale;
|
||||
unlock();
|
||||
|
||||
report.timestamp = msg.getUtcTimestamp().toUSec();
|
||||
if (report.timestamp == 0) {
|
||||
report.timestamp = msg.getMonotonicTimestamp().toUSec();
|
||||
}
|
||||
|
||||
report.x = (msg.magnetic_field[0] - _scale.x_offset) * _scale.x_scale;
|
||||
report.y = (msg.magnetic_field[1] - _scale.y_offset) * _scale.y_scale;
|
||||
report.z = (msg.magnetic_field[2] - _scale.z_offset) * _scale.z_scale;
|
||||
|
||||
publish(msg.getSrcNodeID().get(), &report);
|
||||
publish(msg.getSrcNodeID().get(), &_report);
|
||||
}
|
||||
|
||||
@@ -54,6 +54,7 @@ public:
|
||||
int init() override;
|
||||
|
||||
private:
|
||||
ssize_t read(struct file *filp, char *buffer, size_t buflen);
|
||||
int ioctl(struct file *filp, int cmd, unsigned long arg) override;
|
||||
|
||||
void mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg);
|
||||
@@ -65,4 +66,5 @@ private:
|
||||
|
||||
uavcan::Subscriber<uavcan::equipment::ahrs::Magnetometer, MagCbBinder> _sub_mag;
|
||||
mag_scale _scale = {};
|
||||
mag_report _report = {};
|
||||
};
|
||||
|
||||
@@ -46,6 +46,8 @@
|
||||
#include <arch/board/board.h>
|
||||
#include <arch/chip/chip.h>
|
||||
|
||||
#include <uORB/topics/esc_status.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_pwm_output.h>
|
||||
|
||||
@@ -269,6 +271,24 @@ void UavcanNode::node_spin_once()
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
add a fd to the list of polled events. This assumes you want
|
||||
POLLIN for now.
|
||||
*/
|
||||
int UavcanNode::add_poll_fd(int fd)
|
||||
{
|
||||
int ret = _poll_fds_num;
|
||||
if (_poll_fds_num >= UAVCAN_NUM_POLL_FDS) {
|
||||
errx(1, "uavcan: too many poll fds, exiting");
|
||||
}
|
||||
_poll_fds[_poll_fds_num] = ::pollfd();
|
||||
_poll_fds[_poll_fds_num].fd = fd;
|
||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
||||
_poll_fds_num += 1;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
int UavcanNode::run()
|
||||
{
|
||||
(void)pthread_mutex_lock(&_node_mutex);
|
||||
@@ -280,9 +300,9 @@ int UavcanNode::run()
|
||||
|
||||
_armed_sub = orb_subscribe(ORB_ID(actuator_armed));
|
||||
_test_motor_sub = orb_subscribe(ORB_ID(test_motor));
|
||||
_actuator_direct_sub = orb_subscribe(ORB_ID(actuator_direct));
|
||||
|
||||
actuator_outputs_s outputs;
|
||||
memset(&outputs, 0, sizeof(outputs));
|
||||
memset(&_outputs, 0, sizeof(_outputs));
|
||||
|
||||
const int busevent_fd = ::open(uavcan_stm32::BusEvent::DevName, 0);
|
||||
if (busevent_fd < 0)
|
||||
@@ -304,11 +324,15 @@ int UavcanNode::run()
|
||||
* the value returned from poll() to detect whether actuator control has timed out or not.
|
||||
* Instead, all ORB events need to be checked individually (see below).
|
||||
*/
|
||||
_poll_fds_num = 0;
|
||||
_poll_fds[_poll_fds_num] = ::pollfd();
|
||||
_poll_fds[_poll_fds_num].fd = busevent_fd;
|
||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
||||
_poll_fds_num += 1;
|
||||
add_poll_fd(busevent_fd);
|
||||
|
||||
/*
|
||||
* setup poll to look for actuator direct input if we are
|
||||
* subscribed to the topic
|
||||
*/
|
||||
if (_actuator_direct_sub != -1) {
|
||||
_actuator_direct_poll_fd_num = add_poll_fd(_actuator_direct_sub);
|
||||
}
|
||||
|
||||
while (!_task_should_exit) {
|
||||
// update actuator controls subscriptions if needed
|
||||
@@ -326,6 +350,8 @@ int UavcanNode::run()
|
||||
|
||||
node_spin_once(); // Non-blocking
|
||||
|
||||
bool new_output = false;
|
||||
|
||||
// this would be bad...
|
||||
if (poll_ret < 0) {
|
||||
log("poll error %d", errno);
|
||||
@@ -333,24 +359,39 @@ int UavcanNode::run()
|
||||
} else {
|
||||
// get controls for required topics
|
||||
bool controls_updated = false;
|
||||
unsigned poll_id = 1;
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (_control_subs[i] > 0) {
|
||||
if (_poll_fds[poll_id].revents & POLLIN) {
|
||||
if (_poll_fds[_poll_ids[i]].revents & POLLIN) {
|
||||
controls_updated = true;
|
||||
orb_copy(_control_topics[i], _control_subs[i], &_controls[i]);
|
||||
}
|
||||
poll_id++;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
see if we have any direct actuator updates
|
||||
*/
|
||||
if (_actuator_direct_sub != -1 &&
|
||||
(_poll_fds[_actuator_direct_poll_fd_num].revents & POLLIN) &&
|
||||
orb_copy(ORB_ID(actuator_direct), _actuator_direct_sub, &_actuator_direct) == OK &&
|
||||
!_test_in_progress) {
|
||||
if (_actuator_direct.nvalues > NUM_ACTUATOR_OUTPUTS) {
|
||||
_actuator_direct.nvalues = NUM_ACTUATOR_OUTPUTS;
|
||||
}
|
||||
memcpy(&_outputs.output[0], &_actuator_direct.values[0],
|
||||
_actuator_direct.nvalues*sizeof(float));
|
||||
_outputs.noutputs = _actuator_direct.nvalues;
|
||||
new_output = true;
|
||||
}
|
||||
|
||||
// can we mix?
|
||||
if (_test_in_progress) {
|
||||
float test_outputs[NUM_ACTUATOR_OUTPUTS] = {};
|
||||
test_outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f;
|
||||
|
||||
// Output to the bus
|
||||
_esc_controller.update_outputs(test_outputs, NUM_ACTUATOR_OUTPUTS);
|
||||
memset(&_outputs, 0, sizeof(_outputs));
|
||||
if (_test_motor.motor_number < NUM_ACTUATOR_OUTPUTS) {
|
||||
_outputs.output[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f;
|
||||
_outputs.noutputs = _test_motor.motor_number+1;
|
||||
}
|
||||
new_output = true;
|
||||
} else if (controls_updated && (_mixers != nullptr)) {
|
||||
|
||||
// XXX one output group has 8 outputs max,
|
||||
@@ -358,39 +399,41 @@ int UavcanNode::run()
|
||||
unsigned num_outputs_max = 8;
|
||||
|
||||
// Do mixing
|
||||
outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs_max);
|
||||
outputs.timestamp = hrt_absolute_time();
|
||||
_outputs.noutputs = _mixers->mix(&_outputs.output[0], num_outputs_max);
|
||||
|
||||
// iterate actuators
|
||||
for (unsigned i = 0; i < outputs.noutputs; i++) {
|
||||
// last resort: catch NaN, INF and out-of-band errors
|
||||
if (!isfinite(outputs.output[i])) {
|
||||
/*
|
||||
* Value is NaN, INF or out of band - set to the minimum value.
|
||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||
* spinning motors. It would be deadly in flight.
|
||||
*/
|
||||
outputs.output[i] = -1.0f;
|
||||
}
|
||||
|
||||
// limit outputs to valid range
|
||||
|
||||
// never go below min
|
||||
if (outputs.output[i] < -1.0f) {
|
||||
outputs.output[i] = -1.0f;
|
||||
}
|
||||
|
||||
// never go below max
|
||||
if (outputs.output[i] > 1.0f) {
|
||||
outputs.output[i] = 1.0f;
|
||||
}
|
||||
}
|
||||
|
||||
// Output to the bus
|
||||
_esc_controller.update_outputs(outputs.output, outputs.noutputs);
|
||||
new_output = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (new_output) {
|
||||
// iterate actuators, checking for valid values
|
||||
for (uint8_t i = 0; i < _outputs.noutputs; i++) {
|
||||
// last resort: catch NaN, INF and out-of-band errors
|
||||
if (!isfinite(_outputs.output[i])) {
|
||||
/*
|
||||
* Value is NaN, INF or out of band - set to the minimum value.
|
||||
* This will be clearly visible on the servo status and will limit the risk of accidentally
|
||||
* spinning motors. It would be deadly in flight.
|
||||
*/
|
||||
_outputs.output[i] = -1.0f;
|
||||
}
|
||||
|
||||
// never go below min
|
||||
if (_outputs.output[i] < -1.0f) {
|
||||
_outputs.output[i] = -1.0f;
|
||||
}
|
||||
|
||||
// never go above max
|
||||
if (_outputs.output[i] > 1.0f) {
|
||||
_outputs.output[i] = 1.0f;
|
||||
}
|
||||
}
|
||||
// Output to the bus
|
||||
_outputs.timestamp = hrt_absolute_time();
|
||||
_esc_controller.update_outputs(_outputs.output, _outputs.noutputs);
|
||||
}
|
||||
|
||||
|
||||
// Check motor test state
|
||||
bool updated = false;
|
||||
orb_check(_test_motor_sub, &updated);
|
||||
@@ -459,7 +502,6 @@ UavcanNode::subscribe()
|
||||
uint32_t sub_groups = _groups_required & ~_groups_subscribed;
|
||||
uint32_t unsub_groups = _groups_subscribed & ~_groups_required;
|
||||
// the first fd used by CAN
|
||||
_poll_fds_num = 1;
|
||||
for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) {
|
||||
if (sub_groups & (1 << i)) {
|
||||
warnx("subscribe to actuator_controls_%d", i);
|
||||
@@ -472,9 +514,7 @@ UavcanNode::subscribe()
|
||||
}
|
||||
|
||||
if (_control_subs[i] > 0) {
|
||||
_poll_fds[_poll_fds_num].fd = _control_subs[i];
|
||||
_poll_fds[_poll_fds_num].events = POLLIN;
|
||||
_poll_fds_num++;
|
||||
_poll_ids[i] = add_poll_fd(_control_subs[i]);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -572,6 +612,36 @@ UavcanNode::print_info()
|
||||
(unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num);
|
||||
printf("ESC mixer: %s\n", (_mixers == nullptr) ? "NONE" : "OK");
|
||||
|
||||
if (_outputs.noutputs != 0) {
|
||||
printf("ESC output: ");
|
||||
|
||||
for (uint8_t i=0; i<_outputs.noutputs; i++) {
|
||||
printf("%d ", (int)(_outputs.output[i]*1000));
|
||||
}
|
||||
printf("\n");
|
||||
|
||||
// ESC status
|
||||
int esc_sub = orb_subscribe(ORB_ID(esc_status));
|
||||
struct esc_status_s esc;
|
||||
memset(&esc, 0, sizeof(esc));
|
||||
orb_copy(ORB_ID(esc_status), esc_sub, &esc);
|
||||
|
||||
printf("ESC Status:\n");
|
||||
printf("Addr\tV\tA\tTemp\tSetpt\tRPM\tErr\n");
|
||||
for (uint8_t i=0; i<_outputs.noutputs; i++) {
|
||||
printf("%d\t", esc.esc[i].esc_address);
|
||||
printf("%3.2f\t", (double)esc.esc[i].esc_voltage);
|
||||
printf("%3.2f\t", (double)esc.esc[i].esc_current);
|
||||
printf("%3.2f\t", (double)esc.esc[i].esc_temperature);
|
||||
printf("%3.2f\t", (double)esc.esc[i].esc_setpoint);
|
||||
printf("%d\t", esc.esc[i].esc_rpm);
|
||||
printf("%d", esc.esc[i].esc_errorcount);
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
orb_unsubscribe(esc_sub);
|
||||
}
|
||||
|
||||
// Sensor bridges
|
||||
auto br = _sensor_bridges.getHead();
|
||||
while (br != nullptr) {
|
||||
@@ -590,7 +660,7 @@ UavcanNode::print_info()
|
||||
static void print_usage()
|
||||
{
|
||||
warnx("usage: \n"
|
||||
"\tuavcan {start|status|stop}");
|
||||
"\tuavcan {start|status|stop|arm|disarm}");
|
||||
}
|
||||
|
||||
extern "C" __EXPORT int uavcan_main(int argc, char *argv[]);
|
||||
@@ -637,6 +707,16 @@ int uavcan_main(int argc, char *argv[])
|
||||
::exit(0);
|
||||
}
|
||||
|
||||
if (!std::strcmp(argv[1], "arm")) {
|
||||
inst->arm_actuators(true);
|
||||
::exit(0);
|
||||
}
|
||||
|
||||
if (!std::strcmp(argv[1], "disarm")) {
|
||||
inst->arm_actuators(false);
|
||||
::exit(0);
|
||||
}
|
||||
|
||||
if (!std::strcmp(argv[1], "stop")) {
|
||||
delete inst;
|
||||
::exit(0);
|
||||
|
||||
@@ -42,6 +42,7 @@
|
||||
#include <uORB/topics/actuator_outputs.h>
|
||||
#include <uORB/topics/actuator_armed.h>
|
||||
#include <uORB/topics/test_motor.h>
|
||||
#include <uORB/topics/actuator_direct.h>
|
||||
|
||||
#include "actuators/esc.hpp"
|
||||
#include "sensors/sensor_bridge.hpp"
|
||||
@@ -57,6 +58,9 @@
|
||||
#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4
|
||||
#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc"
|
||||
|
||||
// we add two to allow for actuator_direct and busevent
|
||||
#define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+2)
|
||||
|
||||
/**
|
||||
* A UAVCAN node.
|
||||
*/
|
||||
@@ -97,6 +101,8 @@ private:
|
||||
int init(uavcan::NodeID node_id);
|
||||
void node_spin_once();
|
||||
int run();
|
||||
int add_poll_fd(int fd); ///< add a fd to poll list, returning index into _poll_fds[]
|
||||
|
||||
|
||||
int _task = -1; ///< handle to the OS task
|
||||
bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
|
||||
@@ -125,6 +131,15 @@ private:
|
||||
int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {};
|
||||
pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN + 1] = {}; ///< +1 for /dev/uavcan/busevent
|
||||
pollfd _poll_fds[UAVCAN_NUM_POLL_FDS] = {};
|
||||
unsigned _poll_fds_num = 0;
|
||||
|
||||
int _actuator_direct_sub = -1; ///< uORB subscription of the actuator_direct topic
|
||||
uint8_t _actuator_direct_poll_fd_num;
|
||||
actuator_direct_s _actuator_direct;
|
||||
|
||||
actuator_outputs_s _outputs;
|
||||
|
||||
// index into _poll_fds for each _control_subs handle
|
||||
uint8_t _poll_ids[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN];
|
||||
};
|
||||
|
||||
@@ -59,9 +59,10 @@ __EXPORT int motor_test_main(int argc, char *argv[]);
|
||||
static void motor_test(unsigned channel, float value);
|
||||
static void usage(const char *reason);
|
||||
|
||||
static orb_advert_t _test_motor_pub;
|
||||
|
||||
void motor_test(unsigned channel, float value)
|
||||
{
|
||||
orb_advert_t _test_motor_pub;
|
||||
struct test_motor_s _test_motor;
|
||||
|
||||
_test_motor.motor_number = channel;
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
# 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
|
||||
@@ -32,10 +32,10 @@
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Mathlib / operations demo application
|
||||
# Dump file utility
|
||||
#
|
||||
|
||||
MODULE_COMMAND = math_demo
|
||||
MODULE_STACKSIZE = 12000
|
||||
MODULE_COMMAND = reflect
|
||||
SRCS = reflect.c
|
||||
|
||||
SRCS = math_demo.cpp
|
||||
MAXOPTIMIZATION = -Os
|
||||
@@ -1,7 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
|
||||
* Author: James Goppert
|
||||
* Copyright (c) 2014 Andrew Tridgell. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -33,74 +32,80 @@
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file math_demo.cpp
|
||||
* @author James Goppert
|
||||
* Demonstration of math library
|
||||
* @file reflect.c
|
||||
*
|
||||
* simple data reflector for load testing terminals (especially USB)
|
||||
*
|
||||
* @author Andrew Tridgell
|
||||
*/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include <systemlib/systemlib.h>
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <stdlib.h>
|
||||
#include <stdbool.h>
|
||||
#include <assert.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
/**
|
||||
* Management function.
|
||||
*/
|
||||
extern "C" __EXPORT int math_demo_main(int argc, char *argv[]);
|
||||
__EXPORT int reflect_main(int argc, char *argv[]);
|
||||
|
||||
/**
|
||||
* Test function
|
||||
*/
|
||||
void test();
|
||||
// memory corruption checking
|
||||
#define MAX_BLOCKS 1000
|
||||
static uint32_t nblocks;
|
||||
struct block {
|
||||
uint32_t v[256];
|
||||
};
|
||||
static struct block *blocks[MAX_BLOCKS];
|
||||
|
||||
/**
|
||||
* Print the correct usage.
|
||||
*/
|
||||
static void usage(const char *reason);
|
||||
#define VALUE(i) ((i*7) ^ 0xDEADBEEF)
|
||||
|
||||
static void
|
||||
usage(const char *reason)
|
||||
static void allocate_blocks(void)
|
||||
{
|
||||
if (reason)
|
||||
fprintf(stderr, "%s\n", reason);
|
||||
fprintf(stderr, "usage: math_demo {test}\n\n");
|
||||
exit(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* The deamon app only briefly exists to start
|
||||
* the background job. The stack size assigned in the
|
||||
* Makefile does only apply to this management task.
|
||||
*
|
||||
* The actual stack size should be set in the call
|
||||
* to task_create().
|
||||
*/
|
||||
int math_demo_main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
if (argc < 1)
|
||||
usage("missing command");
|
||||
|
||||
if (!strcmp(argv[1], "test")) {
|
||||
test();
|
||||
exit(0);
|
||||
while (nblocks < MAX_BLOCKS) {
|
||||
blocks[nblocks] = calloc(1, sizeof(struct block));
|
||||
if (blocks[nblocks] == NULL) {
|
||||
break;
|
||||
}
|
||||
for (uint32_t i=0; i<sizeof(blocks[nblocks]->v)/sizeof(uint32_t); i++) {
|
||||
blocks[nblocks]->v[i] = VALUE(i);
|
||||
}
|
||||
nblocks++;
|
||||
}
|
||||
|
||||
usage("unrecognized command");
|
||||
exit(1);
|
||||
printf("Allocated %u blocks\n", nblocks);
|
||||
}
|
||||
|
||||
void test()
|
||||
static void check_blocks(void)
|
||||
{
|
||||
printf("beginning math lib test\n");
|
||||
using namespace math;
|
||||
vectorTest();
|
||||
matrixTest();
|
||||
vector3Test();
|
||||
eulerAnglesTest();
|
||||
quaternionTest();
|
||||
dcmTest();
|
||||
for (uint32_t n=0; n<nblocks; n++) {
|
||||
for (uint32_t i=0; i<sizeof(blocks[nblocks]->v)/sizeof(uint32_t); i++) {
|
||||
assert(blocks[n]->v[i] == VALUE(i));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
int
|
||||
reflect_main(int argc, char *argv[])
|
||||
{
|
||||
uint32_t total = 0;
|
||||
printf("Starting reflector\n");
|
||||
|
||||
allocate_blocks();
|
||||
|
||||
while (true) {
|
||||
char buf[128];
|
||||
ssize_t n = read(0, buf, sizeof(buf));
|
||||
if (n < 0) {
|
||||
break;
|
||||
}
|
||||
if (n > 0) {
|
||||
write(1, buf, n);
|
||||
}
|
||||
total += n;
|
||||
if (total > 1024000) {
|
||||
check_blocks();
|
||||
total = 0;
|
||||
}
|
||||
}
|
||||
return OK;
|
||||
}
|
||||
+1
-1
Submodule uavcan updated: 4de0338824...1efd244275
Reference in New Issue
Block a user