mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
Merge branch 'master' into export-build
This commit is contained in:
Executable → Regular
+586
-224
File diff suppressed because it is too large
Load Diff
@@ -0,0 +1,107 @@
|
||||
#!nsh
|
||||
|
||||
# Disable USB and autostart
|
||||
set USB no
|
||||
set MODE camflyer
|
||||
|
||||
#
|
||||
# Start the ORB (first app to start)
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Load microSD params
|
||||
#
|
||||
echo "[init] loading microSD params"
|
||||
param select /fs/microsd/parameters
|
||||
if [ -f /fs/microsd/parameters ]
|
||||
then
|
||||
param load /fs/microsd/parameters
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 1
|
||||
|
||||
#
|
||||
# Check if PX4IO Firmware should be upgraded (from Andrew Tridgell)
|
||||
#
|
||||
if [ -f /fs/microsd/px4io.bin ]
|
||||
then
|
||||
echo "PX4IO Firmware found. Checking Upgrade.."
|
||||
if cmp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
then
|
||||
echo "No newer version, skipping upgrade."
|
||||
else
|
||||
echo "Loading /fs/microsd/px4io.bin"
|
||||
if px4io update /fs/microsd/px4io.bin > /fs/microsd/px4io_update.log
|
||||
then
|
||||
cp /fs/microsd/px4io.bin /fs/microsd/px4io.bin.current
|
||||
echo "Flashed /fs/microsd/px4io.bin OK" >> /fs/microsd/px4io_update.log
|
||||
else
|
||||
echo "Failed flashing /fs/microsd/px4io.bin" >> /fs/microsd/px4io_update.log
|
||||
echo "Failed to upgrade PX4IO firmware - check if PX4IO is in bootloader mode"
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
|
||||
#
|
||||
# Start MAVLink (depends on orb)
|
||||
#
|
||||
mavlink start -d /dev/ttyS1 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander (depends on orb, mavlink)
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start PX4IO interface (depends on orb, commander)
|
||||
#
|
||||
px4io start
|
||||
|
||||
#
|
||||
# Allow PX4IO to recover from midair restarts.
|
||||
# this is very unlikely, but quite safe and robust.
|
||||
px4io recovery
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start GPS interface (depends on orb)
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start the attitude estimator (depends on orb)
|
||||
#
|
||||
kalman_demo start
|
||||
|
||||
#
|
||||
# Load mixer and start controllers (depends on px4io)
|
||||
#
|
||||
mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
|
||||
control_demo start
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
#sdlog start -s 4
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
@@ -0,0 +1,99 @@
|
||||
#!nsh
|
||||
#
|
||||
# Flight startup script for PX4FMU on PX4IOAR carrier board.
|
||||
#
|
||||
|
||||
# Disable the USB interface
|
||||
set USB no
|
||||
|
||||
# Disable autostarting other apps
|
||||
set MODE ardrone
|
||||
|
||||
echo "[init] doing PX4IOAR startup..."
|
||||
|
||||
#
|
||||
# Start the ORB
|
||||
#
|
||||
uorb start
|
||||
|
||||
#
|
||||
# Init the parameter storage
|
||||
#
|
||||
echo "[init] loading microSD params"
|
||||
param select /fs/microsd/parameters
|
||||
if [ -f /fs/microsd/parameters ]
|
||||
then
|
||||
param load /fs/microsd/parameters
|
||||
fi
|
||||
|
||||
#
|
||||
# Force some key parameters to sane values
|
||||
# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
|
||||
# see https://pixhawk.ethz.ch/mavlink/
|
||||
#
|
||||
param set MAV_TYPE 2
|
||||
|
||||
#
|
||||
# Configure PX4FMU for operation with PX4IOAR
|
||||
#
|
||||
fmu mode_gpio_serial
|
||||
|
||||
#
|
||||
# Start the sensors.
|
||||
#
|
||||
sh /etc/init.d/rc.sensors
|
||||
|
||||
#
|
||||
# Start MAVLink
|
||||
#
|
||||
mavlink start -d /dev/ttyS0 -b 57600
|
||||
usleep 5000
|
||||
|
||||
#
|
||||
# Start the commander.
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Start the attitude estimator
|
||||
#
|
||||
attitude_estimator_ekf start
|
||||
|
||||
#
|
||||
# Fire up the multi rotor attitude controller
|
||||
#
|
||||
multirotor_att_control start
|
||||
|
||||
#
|
||||
# Fire up the AR.Drone interface.
|
||||
#
|
||||
ardrone_interface start -d /dev/ttyS1
|
||||
|
||||
#
|
||||
# Start logging
|
||||
#
|
||||
sdlog start -s 10
|
||||
|
||||
#
|
||||
# Start GPS capture
|
||||
#
|
||||
gps start
|
||||
|
||||
#
|
||||
# Start system state
|
||||
#
|
||||
if blinkm start
|
||||
then
|
||||
echo "using BlinkM for state indication"
|
||||
blinkm systemstate
|
||||
else
|
||||
echo "no BlinkM found, OK."
|
||||
fi
|
||||
|
||||
#
|
||||
# startup is done; we don't want the shell because we
|
||||
# use the same UART for telemetry
|
||||
#
|
||||
echo "[init] startup done"
|
||||
|
||||
exit
|
||||
@@ -35,6 +35,17 @@ param set MAV_TYPE 1
|
||||
#
|
||||
commander start
|
||||
|
||||
#
|
||||
# Check if we got an IO
|
||||
#
|
||||
if [ px4io start ]
|
||||
then
|
||||
echo "IO started"
|
||||
else
|
||||
fmu mode_serial
|
||||
echo "FMU started"
|
||||
end
|
||||
|
||||
#
|
||||
# Start the sensors (depends on orb, px4io)
|
||||
#
|
||||
|
||||
Executable
+83
@@ -0,0 +1,83 @@
|
||||
#!nsh
|
||||
#
|
||||
# PX4FMU startup script.
|
||||
#
|
||||
# This script is responsible for:
|
||||
#
|
||||
# - mounting the microSD card (if present)
|
||||
# - running the user startup script from the microSD card (if present)
|
||||
# - detecting the configuration of the system and picking a suitable
|
||||
# startup script to continue with
|
||||
#
|
||||
# Note: DO NOT add configuration-specific commands to this script;
|
||||
# add them to the per-configuration scripts instead.
|
||||
#
|
||||
|
||||
#
|
||||
# Default to auto-start mode. An init script on the microSD card
|
||||
# can change this to prevent automatic startup of the flight script.
|
||||
#
|
||||
set MODE autostart
|
||||
set USB autoconnect
|
||||
|
||||
#
|
||||
|
||||
#
|
||||
|
||||
|
||||
#
|
||||
# Try to mount the microSD card.
|
||||
#
|
||||
echo "[init] looking for microSD..."
|
||||
if mount -t vfat /dev/mmcsd0 /fs/microsd
|
||||
then
|
||||
echo "[init] card mounted at /fs/microsd"
|
||||
# Start playing the startup tune
|
||||
tone_alarm start
|
||||
else
|
||||
echo "[init] no microSD card found"
|
||||
# Play SOS
|
||||
tone_alarm 2
|
||||
fi
|
||||
|
||||
#
|
||||
# Look for an init script on the microSD card.
|
||||
#
|
||||
# To prevent automatic startup in the current flight mode,
|
||||
# the script should set MODE to some other value.
|
||||
#
|
||||
if [ -f /fs/microsd/etc/rc ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc"
|
||||
sh /fs/microsd/etc/rc
|
||||
fi
|
||||
# Also consider rc.txt files
|
||||
if [ -f /fs/microsd/etc/rc.txt ]
|
||||
then
|
||||
echo "[init] reading /fs/microsd/etc/rc.txt"
|
||||
sh /fs/microsd/etc/rc.txt
|
||||
fi
|
||||
|
||||
#
|
||||
# Check for USB host
|
||||
#
|
||||
if [ $USB != autoconnect ]
|
||||
then
|
||||
echo "[init] not connecting USB"
|
||||
else
|
||||
if sercon
|
||||
then
|
||||
echo "[init] USB interface connected"
|
||||
else
|
||||
echo "[init] No USB connected"
|
||||
fi
|
||||
fi
|
||||
|
||||
# if this is an APM build then there will be a rc.APM script
|
||||
# from an EXTERNAL_SCRIPTS build option
|
||||
if [ -f /etc/init.d/rc.APM ]
|
||||
then
|
||||
echo Running rc.APM
|
||||
# if APM startup is successful then nsh will exit
|
||||
sh /etc/init.d/rc.APM
|
||||
fi
|
||||
@@ -35,8 +35,9 @@ APPNAME = attitude_estimator_ekf
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 2048
|
||||
|
||||
CSRCS = attitude_estimator_ekf_main.c \
|
||||
attitude_estimator_ekf_params.c \
|
||||
CXXSRCS = attitude_estimator_ekf_main.cpp
|
||||
|
||||
CSRCS = attitude_estimator_ekf_params.c \
|
||||
codegen/eye.c \
|
||||
codegen/attitudeKalmanfilter.c \
|
||||
codegen/mrdivide.c \
|
||||
|
||||
+12
-5
@@ -66,11 +66,17 @@
|
||||
#include <systemlib/perf_counter.h>
|
||||
#include <systemlib/err.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
#include "codegen/attitudeKalmanfilter_initialize.h"
|
||||
#include "codegen/attitudeKalmanfilter.h"
|
||||
#include "attitude_estimator_ekf_params.h"
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
__EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
extern "C" __EXPORT int attitude_estimator_ekf_main(int argc, char *argv[]);
|
||||
|
||||
static bool thread_should_exit = false; /**< Deamon exit flag */
|
||||
static bool thread_running = false; /**< Deamon status flag */
|
||||
@@ -265,10 +271,11 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds
|
||||
/* Main loop*/
|
||||
while (!thread_should_exit) {
|
||||
|
||||
struct pollfd fds[2] = {
|
||||
{ .fd = sub_raw, .events = POLLIN },
|
||||
{ .fd = sub_params, .events = POLLIN }
|
||||
};
|
||||
struct pollfd fds[2];
|
||||
fds[0].fd = sub_raw;
|
||||
fds[0].events = POLLIN;
|
||||
fds[1].fd = sub_params;
|
||||
fds[1].events = POLLIN;
|
||||
int ret = poll(fds, 2, 1000);
|
||||
|
||||
if (ret < 0) {
|
||||
@@ -33,7 +33,14 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/* @file U-Blox protocol implementation */
|
||||
/**
|
||||
* @file ubx.cpp
|
||||
*
|
||||
* U-Blox protocol implementation. Following u-blox 6/7 Receiver Description
|
||||
* including Prototol Specification.
|
||||
*
|
||||
* @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf
|
||||
*/
|
||||
|
||||
#include <unistd.h>
|
||||
#include <stdio.h>
|
||||
@@ -113,13 +120,15 @@ UBX::configure(unsigned &baudrate)
|
||||
cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK;
|
||||
|
||||
send_config_packet(_fd, (uint8_t*)&cfg_prt_packet, sizeof(cfg_prt_packet));
|
||||
|
||||
/* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */
|
||||
receive(UBX_CONFIG_TIMEOUT);
|
||||
|
||||
if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) {
|
||||
set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE);
|
||||
baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE;
|
||||
}
|
||||
|
||||
/* no ack is ecpected here, keep going configuring */
|
||||
|
||||
/* send a CFT-RATE message to define update rate */
|
||||
type_gps_bin_cfg_rate_packet_t cfg_rate_packet;
|
||||
memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet));
|
||||
@@ -631,16 +640,17 @@ UBX::handle_message()
|
||||
}
|
||||
|
||||
case NAV_VELNED: {
|
||||
// printf("GOT NAV_VELNED MESSAGE\n");
|
||||
|
||||
if (!_waiting_for_ack) {
|
||||
/* 35.15 NAV-VELNED (0x01 0x12) message (page 181 / 210 of reference manual */
|
||||
gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer;
|
||||
|
||||
_gps_position->vel_m_s = (float)packet->speed * 1e-2f;
|
||||
_gps_position->vel_n_m_s = (float)packet->velN * 1e-2f;
|
||||
_gps_position->vel_e_m_s = (float)packet->velE * 1e-2f;
|
||||
_gps_position->vel_d_m_s = (float)packet->velD * 1e-2f;
|
||||
_gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */
|
||||
_gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */
|
||||
_gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */
|
||||
_gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f;
|
||||
_gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f;
|
||||
_gps_position->vel_ned_valid = true;
|
||||
_gps_position->timestamp_velocity = hrt_absolute_time();
|
||||
}
|
||||
|
||||
@@ -684,9 +684,10 @@ L3GD20::measure()
|
||||
* 74 from all measurements centers them around zero.
|
||||
*/
|
||||
report->timestamp = hrt_absolute_time();
|
||||
/* XXX adjust for sensor alignment to board here */
|
||||
report->x_raw = raw_report.x;
|
||||
report->y_raw = raw_report.y;
|
||||
|
||||
/* swap x and y and negate y */
|
||||
report->x_raw = raw_report.y;
|
||||
report->y_raw = ((raw_report.x == -32768) ? 32767 : -raw_report.x);
|
||||
report->z_raw = raw_report.z;
|
||||
|
||||
report->x = ((report->x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale;
|
||||
|
||||
@@ -355,6 +355,8 @@ int KalmanNav::predictState(float dt)
|
||||
float LDot = vN / R;
|
||||
float lDot = vE / (cosLSing * R);
|
||||
float rotRate = 2 * omega + lDot;
|
||||
|
||||
// XXX position prediction using speed
|
||||
float vNDot = fN - vE * rotRate * sinL +
|
||||
vD * LDot;
|
||||
float vDDot = fD - vE * rotRate * cosL -
|
||||
|
||||
+102
-14
@@ -308,6 +308,14 @@ handle_message(mavlink_message_t *msg)
|
||||
|
||||
uint64_t timestamp = hrt_absolute_time();
|
||||
|
||||
/* TODO, set ground_press/ temp during calib */
|
||||
static const float ground_press = 1013.25f; // mbar
|
||||
static const float ground_tempC = 21.0f;
|
||||
static const float ground_alt = 0.0f;
|
||||
static const float T0 = 273.15;
|
||||
static const float R = 287.05f;
|
||||
static const float g = 9.806f;
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_RAW_IMU) {
|
||||
|
||||
mavlink_raw_imu_t imu;
|
||||
@@ -376,6 +384,87 @@ handle_message(mavlink_message_t *msg)
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_HIGHRES_IMU) {
|
||||
|
||||
mavlink_highres_imu_t imu;
|
||||
mavlink_msg_highres_imu_decode(msg, &imu);
|
||||
|
||||
/* packet counter */
|
||||
static uint16_t hil_counter = 0;
|
||||
static uint16_t hil_frames = 0;
|
||||
static uint64_t old_timestamp = 0;
|
||||
|
||||
/* sensors general */
|
||||
hil_sensors.timestamp = hrt_absolute_time();
|
||||
|
||||
/* hil gyro */
|
||||
static const float mrad2rad = 1.0e-3f;
|
||||
hil_sensors.gyro_counter = hil_counter;
|
||||
hil_sensors.gyro_raw[0] = imu.xgyro / mrad2rad;
|
||||
hil_sensors.gyro_raw[1] = imu.ygyro / mrad2rad;
|
||||
hil_sensors.gyro_raw[2] = imu.zgyro / mrad2rad;
|
||||
hil_sensors.gyro_rad_s[0] = imu.xgyro;
|
||||
hil_sensors.gyro_rad_s[1] = imu.ygyro;
|
||||
hil_sensors.gyro_rad_s[2] = imu.zgyro;
|
||||
|
||||
/* accelerometer */
|
||||
hil_sensors.accelerometer_counter = hil_counter;
|
||||
static const float mg2ms2 = 9.8f / 1000.0f;
|
||||
hil_sensors.accelerometer_raw[0] = imu.xacc / mg2ms2;
|
||||
hil_sensors.accelerometer_raw[1] = imu.yacc / mg2ms2;
|
||||
hil_sensors.accelerometer_raw[2] = imu.zacc / mg2ms2;
|
||||
hil_sensors.accelerometer_m_s2[0] = imu.xacc;
|
||||
hil_sensors.accelerometer_m_s2[1] = imu.yacc;
|
||||
hil_sensors.accelerometer_m_s2[2] = imu.zacc;
|
||||
hil_sensors.accelerometer_mode = 0; // TODO what is this?
|
||||
hil_sensors.accelerometer_range_m_s2 = 32.7f; // int16
|
||||
|
||||
/* adc */
|
||||
hil_sensors.adc_voltage_v[0] = 0;
|
||||
hil_sensors.adc_voltage_v[1] = 0;
|
||||
hil_sensors.adc_voltage_v[2] = 0;
|
||||
|
||||
/* magnetometer */
|
||||
float mga2ga = 1.0e-3f;
|
||||
hil_sensors.magnetometer_counter = hil_counter;
|
||||
hil_sensors.magnetometer_raw[0] = imu.xmag / mga2ga;
|
||||
hil_sensors.magnetometer_raw[1] = imu.ymag / mga2ga;
|
||||
hil_sensors.magnetometer_raw[2] = imu.zmag / mga2ga;
|
||||
hil_sensors.magnetometer_ga[0] = imu.xmag;
|
||||
hil_sensors.magnetometer_ga[1] = imu.ymag;
|
||||
hil_sensors.magnetometer_ga[2] = imu.zmag;
|
||||
hil_sensors.magnetometer_range_ga = 32.7f; // int16
|
||||
hil_sensors.magnetometer_mode = 0; // TODO what is this
|
||||
hil_sensors.magnetometer_cuttoff_freq_hz = 50.0f;
|
||||
|
||||
hil_sensors.baro_pres_mbar = imu.abs_pressure;
|
||||
|
||||
float tempC = imu.temperature;
|
||||
float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
|
||||
float h = ground_alt + (R / g) * tempAvgK * logf(ground_press / imu.abs_pressure);
|
||||
|
||||
hil_sensors.baro_alt_meter = h;
|
||||
hil_sensors.baro_temp_celcius = imu.temperature;
|
||||
|
||||
hil_sensors.gyro_counter = hil_counter;
|
||||
hil_sensors.magnetometer_counter = hil_counter;
|
||||
hil_sensors.accelerometer_counter = hil_counter;
|
||||
|
||||
/* publish */
|
||||
orb_publish(ORB_ID(sensor_combined), pub_hil_sensors, &hil_sensors);
|
||||
|
||||
// increment counters
|
||||
hil_counter++;
|
||||
hil_frames++;
|
||||
|
||||
// output
|
||||
if ((timestamp - old_timestamp) > 10000000) {
|
||||
printf("receiving hil imu at %d hz\n", hil_frames/10);
|
||||
old_timestamp = timestamp;
|
||||
hil_frames = 0;
|
||||
}
|
||||
}
|
||||
|
||||
if (msg->msgid == MAVLINK_MSG_ID_GPS_RAW_INT) {
|
||||
|
||||
mavlink_gps_raw_int_t gps;
|
||||
@@ -388,21 +477,27 @@ handle_message(mavlink_message_t *msg)
|
||||
|
||||
/* gps */
|
||||
hil_gps.timestamp_position = gps.time_usec;
|
||||
// hil_gps.counter = hil_counter++;
|
||||
hil_gps.time_gps_usec = gps.time_usec;
|
||||
hil_gps.lat = gps.lat;
|
||||
hil_gps.lon = gps.lon;
|
||||
hil_gps.alt = gps.alt;
|
||||
// hil_gps.counter_pos_valid = hil_counter++;
|
||||
hil_gps.eph_m = (float)gps.eph * 1e-2f; // from cm to m
|
||||
hil_gps.epv_m = (float)gps.epv * 1e-2f; // from cm to m
|
||||
hil_gps.s_variance_m_s = 100; // XXX 100 m/s variance?
|
||||
hil_gps.p_variance_m = 100; // XXX 100 m variance?
|
||||
hil_gps.s_variance_m_s = 5.0f;
|
||||
hil_gps.p_variance_m = hil_gps.eph_m * hil_gps.eph_m;
|
||||
hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s
|
||||
hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
|
||||
hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(gps.cog * M_DEG_TO_RAD_F * 1e-2f);
|
||||
|
||||
/* gps.cog is in degrees 0..360 * 100, heading is -PI..+PI */
|
||||
float heading_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f;
|
||||
/* go back to -PI..PI */
|
||||
if (heading_rad > M_PI_F)
|
||||
heading_rad -= 2.0f * M_PI_F;
|
||||
hil_gps.vel_n_m_s = (float)gps.vel * 1e-2f * cosf(heading_rad);
|
||||
hil_gps.vel_e_m_s = (float)gps.vel * 1e-2f * sinf(heading_rad);
|
||||
hil_gps.vel_d_m_s = 0.0f;
|
||||
hil_gps.cog_rad = gps.cog * M_DEG_TO_RAD_F * 1e-2f; // from deg*100 to rad
|
||||
hil_gps.vel_ned_valid = true;
|
||||
/* COG (course over ground) is speced as -PI..+PI */
|
||||
hil_gps.cog_rad = heading_rad;
|
||||
hil_gps.fix_type = gps.fix_type;
|
||||
hil_gps.satellites_visible = gps.satellites_visible;
|
||||
|
||||
@@ -435,13 +530,6 @@ handle_message(mavlink_message_t *msg)
|
||||
hil_sensors.timestamp = press.time_usec;
|
||||
|
||||
/* baro */
|
||||
/* TODO, set ground_press/ temp during calib */
|
||||
static const float ground_press = 1013.25f; // mbar
|
||||
static const float ground_tempC = 21.0f;
|
||||
static const float ground_alt = 0.0f;
|
||||
static const float T0 = 273.15;
|
||||
static const float R = 287.05f;
|
||||
static const float g = 9.806f;
|
||||
|
||||
float tempC = press.temperature / 100.0f;
|
||||
float tempAvgK = T0 + (tempC + ground_tempC) / 2.0f;
|
||||
|
||||
@@ -229,6 +229,13 @@ l_vehicle_gps_position(const struct listener *l)
|
||||
/* copy gps data into local buffer */
|
||||
orb_copy(ORB_ID(vehicle_gps_position), mavlink_subs.gps_sub, &gps);
|
||||
|
||||
/* GPS COG is 0..2PI in degrees * 1e2 */
|
||||
float cog_deg = gps.cog_rad;
|
||||
if (cog_deg > M_PI_F)
|
||||
cog_deg -= 2.0f * M_PI_F;
|
||||
cog_deg *= M_RAD_TO_DEG_F;
|
||||
|
||||
|
||||
/* GPS position */
|
||||
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_0,
|
||||
gps.timestamp_position,
|
||||
@@ -236,13 +243,14 @@ l_vehicle_gps_position(const struct listener *l)
|
||||
gps.lat,
|
||||
gps.lon,
|
||||
gps.alt,
|
||||
(uint16_t)(gps.eph_m * 1e2f), // from m to cm
|
||||
(uint16_t)(gps.epv_m * 1e2f), // from m to cm
|
||||
(uint16_t)(gps.vel_m_s * 1e2f), // from m/s to cm/s
|
||||
(uint16_t)(gps.cog_rad * M_RAD_TO_DEG_F * 1e2f), // from rad to deg * 100
|
||||
gps.eph_m * 1e2f, // from m to cm
|
||||
gps.epv_m * 1e2f, // from m to cm
|
||||
gps.vel_m_s * 1e2f, // from m/s to cm/s
|
||||
cog_deg * 1e2f, // from rad to deg * 100
|
||||
gps.satellites_visible);
|
||||
|
||||
if (gps.satellite_info_available && (gps_counter % 4 == 0)) {
|
||||
/* update SAT info every 10 seconds */
|
||||
if (gps.satellite_info_available && (gps_counter % 50 == 0)) {
|
||||
mavlink_msg_gps_status_send(MAVLINK_COMM_0,
|
||||
gps.satellites_visible,
|
||||
gps.satellite_prn,
|
||||
|
||||
@@ -0,0 +1,64 @@
|
||||
############################################################################
|
||||
#
|
||||
# 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
|
||||
# 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.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#
|
||||
# Makefile to build the position estimator
|
||||
#
|
||||
|
||||
APPNAME = position_estimator_mc
|
||||
PRIORITY = SCHED_PRIORITY_DEFAULT
|
||||
STACKSIZE = 4096
|
||||
|
||||
CSRCS = position_estimator_mc_main.c \
|
||||
position_estimator_mc_params.c \
|
||||
codegen/positionKalmanFilter1D_initialize.c \
|
||||
codegen/positionKalmanFilter1D_terminate.c \
|
||||
codegen/positionKalmanFilter1D.c \
|
||||
codegen/rt_nonfinite.c \
|
||||
codegen/rtGetInf.c \
|
||||
codegen/rtGetNaN.c \
|
||||
codegen/positionKalmanFilter1D_dT_initialize.c \
|
||||
codegen/positionKalmanFilter1D_dT_terminate.c \
|
||||
codegen/kalman_dlqe1.c \
|
||||
codegen/kalman_dlqe1_initialize.c \
|
||||
codegen/kalman_dlqe1_terminate.c \
|
||||
codegen/kalman_dlqe2.c \
|
||||
codegen/kalman_dlqe2_initialize.c \
|
||||
codegen/kalman_dlqe2_terminate.c \
|
||||
codegen/kalman_dlqe3.c \
|
||||
codegen/kalman_dlqe3_initialize.c \
|
||||
codegen/kalman_dlqe3_terminate.c \
|
||||
codegen/kalman_dlqe3_data.c \
|
||||
codegen/randn.c
|
||||
|
||||
include $(APPDIR)/mk/app.mk
|
||||
+58
@@ -0,0 +1,58 @@
|
||||
/*
|
||||
* kalman_dlqe1.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:32 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe1.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe1(const real32_T A[9], const real32_T C[3], const real32_T K[3],
|
||||
const real32_T x_aposteriori_k[3], real32_T z, real32_T
|
||||
x_aposteriori[3])
|
||||
{
|
||||
printf("[dlqe input]: x_aposteriori_k %12.8f\t %12.8f\t %12.8f\t z:%12.8f\n", (double)(x_aposteriori_k[0]), (double)(x_aposteriori_k[1]), (double)(x_aposteriori_k[2]), (double)z);
|
||||
printf("[dlqe input]: C[0]: %12.8f\tC[1] %12.8f\tC[2] %12.8f\n", (double)(C[0]), (double)(C[1]), (double)(C[2]));
|
||||
real32_T y;
|
||||
int32_T i0;
|
||||
real32_T b_y[3];
|
||||
int32_T i1;
|
||||
real32_T f0;
|
||||
y = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
b_y[i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
b_y[i0] += C[i1] * A[i1 + 3 * i0];
|
||||
}
|
||||
|
||||
y += b_y[i0] * x_aposteriori_k[i0];
|
||||
}
|
||||
|
||||
y = z - y;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
|
||||
}
|
||||
|
||||
x_aposteriori[i0] = f0 + K[i0] * y;
|
||||
}
|
||||
//printf("[dlqe output]: x_aposteriori %12.8f\t %12.8f\t %12.8f\n", (double)(x_aposteriori[0]), (double)(x_aposteriori[1]), (double)(x_aposteriori[2]));
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe1.c) */
|
||||
+30
@@ -0,0 +1,30 @@
|
||||
/*
|
||||
* kalman_dlqe1.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:32 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE1_H__
|
||||
#define __KALMAN_DLQE1_H__
|
||||
/* Include files */
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe1_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe1(const real32_T A[9], const real32_T C[3], const real32_T K[3], const real32_T x_aposteriori_k[3], real32_T z, real32_T x_aposteriori[3]);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe1.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* kalman_dlqe1_initialize.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1_initialize'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe1.h"
|
||||
#include "kalman_dlqe1_initialize.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe1_initialize(void)
|
||||
{
|
||||
rt_InitInfAndNaN(8U);
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe1_initialize.c) */
|
||||
@@ -0,0 +1,30 @@
|
||||
/*
|
||||
* kalman_dlqe1_initialize.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1_initialize'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE1_INITIALIZE_H__
|
||||
#define __KALMAN_DLQE1_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe1_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe1_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe1_initialize.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* kalman_dlqe1_terminate.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1_terminate'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe1.h"
|
||||
#include "kalman_dlqe1_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe1_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe1_terminate.c) */
|
||||
@@ -0,0 +1,30 @@
|
||||
/*
|
||||
* kalman_dlqe1_terminate.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1_terminate'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:32 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE1_TERMINATE_H__
|
||||
#define __KALMAN_DLQE1_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe1_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe1_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe1_terminate.h) */
|
||||
+16
@@ -0,0 +1,16 @@
|
||||
/*
|
||||
* kalman_dlqe1_types.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe1'
|
||||
*
|
||||
* C source code generated on: Wed Feb 13 20:34:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE1_TYPES_H__
|
||||
#define __KALMAN_DLQE1_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe1_types.h) */
|
||||
+119
@@ -0,0 +1,119 @@
|
||||
/*
|
||||
* kalman_dlqe2.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe2.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
static real32_T rt_powf_snf(real32_T u0, real32_T u1);
|
||||
|
||||
/* Function Definitions */
|
||||
static real32_T rt_powf_snf(real32_T u0, real32_T u1)
|
||||
{
|
||||
real32_T y;
|
||||
real32_T f1;
|
||||
real32_T f2;
|
||||
if (rtIsNaNF(u0) || rtIsNaNF(u1)) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else {
|
||||
f1 = (real32_T)fabs(u0);
|
||||
f2 = (real32_T)fabs(u1);
|
||||
if (rtIsInfF(u1)) {
|
||||
if (f1 == 1.0F) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else if (f1 > 1.0F) {
|
||||
if (u1 > 0.0F) {
|
||||
y = ((real32_T)rtInf);
|
||||
} else {
|
||||
y = 0.0F;
|
||||
}
|
||||
} else if (u1 > 0.0F) {
|
||||
y = 0.0F;
|
||||
} else {
|
||||
y = ((real32_T)rtInf);
|
||||
}
|
||||
} else if (f2 == 0.0F) {
|
||||
y = 1.0F;
|
||||
} else if (f2 == 1.0F) {
|
||||
if (u1 > 0.0F) {
|
||||
y = u0;
|
||||
} else {
|
||||
y = 1.0F / u0;
|
||||
}
|
||||
} else if (u1 == 2.0F) {
|
||||
y = u0 * u0;
|
||||
} else if ((u1 == 0.5F) && (u0 >= 0.0F)) {
|
||||
y = (real32_T)sqrt(u0);
|
||||
} else if ((u0 < 0.0F) && (u1 > (real32_T)floor(u1))) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else {
|
||||
y = (real32_T)pow(u0, u1);
|
||||
}
|
||||
}
|
||||
|
||||
return y;
|
||||
}
|
||||
|
||||
void kalman_dlqe2(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const
|
||||
real32_T x_aposteriori_k[3], real32_T z, real32_T
|
||||
x_aposteriori[3])
|
||||
{
|
||||
//printf("[dqle2] dt: %12.8f\tvk1 %12.8f\tk2: %12.8f\tk3: %12.8f\n", (double)(dt), (double)(k1), (double)(k2), (double)(k3));
|
||||
//printf("[dqle2] dt: %8.4f\n", (double)(dt));//, (double)(k1), (double)(k2), (double)(k3));
|
||||
real32_T A[9];
|
||||
real32_T y;
|
||||
int32_T i0;
|
||||
static const int8_T iv0[3] = { 0, 0, 1 };
|
||||
|
||||
real32_T b_k1[3];
|
||||
int32_T i1;
|
||||
static const int8_T iv1[3] = { 1, 0, 0 };
|
||||
|
||||
real32_T f0;
|
||||
A[0] = 1.0F;
|
||||
A[3] = dt;
|
||||
A[6] = 0.5F * rt_powf_snf(dt, 2.0F);
|
||||
A[1] = 0.0F;
|
||||
A[4] = 1.0F;
|
||||
A[7] = dt;
|
||||
y = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
A[2 + 3 * i0] = (real32_T)iv0[i0];
|
||||
b_k1[i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
b_k1[i0] += (real32_T)iv1[i1] * A[i1 + 3 * i0];
|
||||
}
|
||||
|
||||
y += b_k1[i0] * x_aposteriori_k[i0];
|
||||
}
|
||||
|
||||
y = z - y;
|
||||
b_k1[0] = k1;
|
||||
b_k1[1] = k2;
|
||||
b_k1[2] = k3;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
|
||||
}
|
||||
|
||||
x_aposteriori[i0] = f0 + b_k1[i0] * y;
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe2.c) */
|
||||
+32
@@ -0,0 +1,32 @@
|
||||
/*
|
||||
* kalman_dlqe2.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:29 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE2_H__
|
||||
#define __KALMAN_DLQE2_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe2_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe2(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const real32_T x_aposteriori_k[3], real32_T z, real32_T x_aposteriori[3]);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe2.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* kalman_dlqe2_initialize.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2_initialize'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe2.h"
|
||||
#include "kalman_dlqe2_initialize.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe2_initialize(void)
|
||||
{
|
||||
rt_InitInfAndNaN(8U);
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe2_initialize.c) */
|
||||
@@ -0,0 +1,32 @@
|
||||
/*
|
||||
* kalman_dlqe2_initialize.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2_initialize'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE2_INITIALIZE_H__
|
||||
#define __KALMAN_DLQE2_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe2_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe2_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe2_initialize.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* kalman_dlqe2_terminate.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2_terminate'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe2.h"
|
||||
#include "kalman_dlqe2_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe2_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe2_terminate.c) */
|
||||
@@ -0,0 +1,32 @@
|
||||
/*
|
||||
* kalman_dlqe2_terminate.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2_terminate'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE2_TERMINATE_H__
|
||||
#define __KALMAN_DLQE2_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe2_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe2_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe2_terminate.h) */
|
||||
+16
@@ -0,0 +1,16 @@
|
||||
/*
|
||||
* kalman_dlqe2_types.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe2'
|
||||
*
|
||||
* C source code generated on: Thu Feb 14 12:52:28 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE2_TYPES_H__
|
||||
#define __KALMAN_DLQE2_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe2_types.h) */
|
||||
+137
@@ -0,0 +1,137 @@
|
||||
/*
|
||||
* kalman_dlqe3.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe3.h"
|
||||
#include "randn.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
static real32_T rt_powf_snf(real32_T u0, real32_T u1);
|
||||
|
||||
/* Function Definitions */
|
||||
static real32_T rt_powf_snf(real32_T u0, real32_T u1)
|
||||
{
|
||||
real32_T y;
|
||||
real32_T f1;
|
||||
real32_T f2;
|
||||
if (rtIsNaNF(u0) || rtIsNaNF(u1)) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else {
|
||||
f1 = (real32_T)fabs(u0);
|
||||
f2 = (real32_T)fabs(u1);
|
||||
if (rtIsInfF(u1)) {
|
||||
if (f1 == 1.0F) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else if (f1 > 1.0F) {
|
||||
if (u1 > 0.0F) {
|
||||
y = ((real32_T)rtInf);
|
||||
} else {
|
||||
y = 0.0F;
|
||||
}
|
||||
} else if (u1 > 0.0F) {
|
||||
y = 0.0F;
|
||||
} else {
|
||||
y = ((real32_T)rtInf);
|
||||
}
|
||||
} else if (f2 == 0.0F) {
|
||||
y = 1.0F;
|
||||
} else if (f2 == 1.0F) {
|
||||
if (u1 > 0.0F) {
|
||||
y = u0;
|
||||
} else {
|
||||
y = 1.0F / u0;
|
||||
}
|
||||
} else if (u1 == 2.0F) {
|
||||
y = u0 * u0;
|
||||
} else if ((u1 == 0.5F) && (u0 >= 0.0F)) {
|
||||
y = (real32_T)sqrt(u0);
|
||||
} else if ((u0 < 0.0F) && (u1 > (real32_T)floor(u1))) {
|
||||
y = ((real32_T)rtNaN);
|
||||
} else {
|
||||
y = (real32_T)pow(u0, u1);
|
||||
}
|
||||
}
|
||||
|
||||
return y;
|
||||
}
|
||||
|
||||
void kalman_dlqe3(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const
|
||||
real32_T x_aposteriori_k[3], real32_T z, real32_T posUpdate,
|
||||
real32_T addNoise, real32_T sigma, real32_T x_aposteriori[3])
|
||||
{
|
||||
real32_T A[9];
|
||||
int32_T i0;
|
||||
static const int8_T iv0[3] = { 0, 0, 1 };
|
||||
|
||||
real_T b;
|
||||
real32_T y;
|
||||
real32_T b_y[3];
|
||||
int32_T i1;
|
||||
static const int8_T iv1[3] = { 1, 0, 0 };
|
||||
|
||||
real32_T b_k1[3];
|
||||
real32_T f0;
|
||||
A[0] = 1.0F;
|
||||
A[3] = dt;
|
||||
A[6] = 0.5F * rt_powf_snf(dt, 2.0F);
|
||||
A[1] = 0.0F;
|
||||
A[4] = 1.0F;
|
||||
A[7] = dt;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
A[2 + 3 * i0] = (real32_T)iv0[i0];
|
||||
}
|
||||
|
||||
if (addNoise == 1.0F) {
|
||||
b = randn();
|
||||
z += sigma * (real32_T)b;
|
||||
}
|
||||
|
||||
if (posUpdate != 0.0F) {
|
||||
y = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
b_y[i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
b_y[i0] += (real32_T)iv1[i1] * A[i1 + 3 * i0];
|
||||
}
|
||||
|
||||
y += b_y[i0] * x_aposteriori_k[i0];
|
||||
}
|
||||
|
||||
y = z - y;
|
||||
b_k1[0] = k1;
|
||||
b_k1[1] = k2;
|
||||
b_k1[2] = k3;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
f0 += A[i0 + 3 * i1] * x_aposteriori_k[i1];
|
||||
}
|
||||
|
||||
x_aposteriori[i0] = f0 + b_k1[i0] * y;
|
||||
}
|
||||
} else {
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
x_aposteriori[i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
x_aposteriori[i0] += A[i0 + 3 * i1] * x_aposteriori_k[i1];
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe3.c) */
|
||||
+33
@@ -0,0 +1,33 @@
|
||||
/*
|
||||
* kalman_dlqe3.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:32 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE3_H__
|
||||
#define __KALMAN_DLQE3_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe3_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe3(real32_T dt, real32_T k1, real32_T k2, real32_T k3, const real32_T x_aposteriori_k[3], real32_T z, real32_T posUpdate, real32_T addNoise, real32_T sigma, real32_T x_aposteriori[3]);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe3.h) */
|
||||
+32
@@ -0,0 +1,32 @@
|
||||
/*
|
||||
* kalman_dlqe3_data.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_data'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe3.h"
|
||||
#include "kalman_dlqe3_data.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
uint32_T method;
|
||||
uint32_T state[2];
|
||||
uint32_T b_method;
|
||||
uint32_T b_state;
|
||||
uint32_T c_state[2];
|
||||
boolean_T state_not_empty;
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
/* End of code generation (kalman_dlqe3_data.c) */
|
||||
+38
@@ -0,0 +1,38 @@
|
||||
/*
|
||||
* kalman_dlqe3_data.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_data'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE3_DATA_H__
|
||||
#define __KALMAN_DLQE3_DATA_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe3_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
extern uint32_T method;
|
||||
extern uint32_T state[2];
|
||||
extern uint32_T b_method;
|
||||
extern uint32_T b_state;
|
||||
extern uint32_T c_state[2];
|
||||
extern boolean_T state_not_empty;
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe3_data.h) */
|
||||
@@ -0,0 +1,47 @@
|
||||
/*
|
||||
* kalman_dlqe3_initialize.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_initialize'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe3.h"
|
||||
#include "kalman_dlqe3_initialize.h"
|
||||
#include "kalman_dlqe3_data.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe3_initialize(void)
|
||||
{
|
||||
int32_T i;
|
||||
static const uint32_T uv0[2] = { 362436069U, 0U };
|
||||
|
||||
rt_InitInfAndNaN(8U);
|
||||
state_not_empty = FALSE;
|
||||
b_state = 1144108930U;
|
||||
b_method = 7U;
|
||||
method = 0U;
|
||||
for (i = 0; i < 2; i++) {
|
||||
c_state[i] = 362436069U + 158852560U * (uint32_T)i;
|
||||
state[i] = uv0[i];
|
||||
}
|
||||
|
||||
if (state[1] == 0U) {
|
||||
state[1] = 521288629U;
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe3_initialize.c) */
|
||||
@@ -0,0 +1,33 @@
|
||||
/*
|
||||
* kalman_dlqe3_initialize.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_initialize'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE3_INITIALIZE_H__
|
||||
#define __KALMAN_DLQE3_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe3_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe3_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe3_initialize.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* kalman_dlqe3_terminate.c
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_terminate'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "kalman_dlqe3.h"
|
||||
#include "kalman_dlqe3_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void kalman_dlqe3_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (kalman_dlqe3_terminate.c) */
|
||||
@@ -0,0 +1,33 @@
|
||||
/*
|
||||
* kalman_dlqe3_terminate.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3_terminate'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:31 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE3_TERMINATE_H__
|
||||
#define __KALMAN_DLQE3_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
#include <string.h>
|
||||
#include "rt_nonfinite.h"
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "kalman_dlqe3_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void kalman_dlqe3_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe3_terminate.h) */
|
||||
+16
@@ -0,0 +1,16 @@
|
||||
/*
|
||||
* kalman_dlqe3_types.h
|
||||
*
|
||||
* Code generation for function 'kalman_dlqe3'
|
||||
*
|
||||
* C source code generated on: Tue Feb 19 15:26:30 2013
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __KALMAN_DLQE3_TYPES_H__
|
||||
#define __KALMAN_DLQE3_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (kalman_dlqe3_types.h) */
|
||||
+136
@@ -0,0 +1,136 @@
|
||||
/*
|
||||
* positionKalmanFilter1D.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D(const real32_T A[9], const real32_T B[3], const
|
||||
real32_T C[3], const real32_T x_aposteriori_k[3], const real32_T
|
||||
P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T
|
||||
Q[9], real32_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3],
|
||||
real32_T P_aposteriori[9])
|
||||
{
|
||||
int32_T i0;
|
||||
real32_T f0;
|
||||
int32_T k;
|
||||
real32_T b_A[9];
|
||||
int32_T i1;
|
||||
real32_T P_apriori[9];
|
||||
real32_T y;
|
||||
real32_T K[3];
|
||||
real32_T S;
|
||||
int8_T I[9];
|
||||
|
||||
/* prediction */
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (k = 0; k < 3; k++) {
|
||||
f0 += A[i0 + 3 * k] * x_aposteriori_k[k];
|
||||
}
|
||||
|
||||
x_aposteriori[i0] = f0 + B[i0] * u;
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
b_A[i0 + 3 * k] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
b_A[i0 + 3 * k] += A[i0 + 3 * i1] * P_aposteriori_k[i1 + 3 * k];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
f0 = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
f0 += b_A[i0 + 3 * i1] * A[k + 3 * i1];
|
||||
}
|
||||
|
||||
P_apriori[i0 + 3 * k] = f0 + Q[i0 + 3 * k];
|
||||
}
|
||||
}
|
||||
|
||||
if ((real32_T)fabs(u) < thresh) {
|
||||
x_aposteriori[1] *= decay;
|
||||
}
|
||||
|
||||
/* update */
|
||||
if (gps_update == 1) {
|
||||
y = 0.0F;
|
||||
for (k = 0; k < 3; k++) {
|
||||
y += C[k] * x_aposteriori[k];
|
||||
K[k] = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
K[k] += C[i0] * P_apriori[i0 + 3 * k];
|
||||
}
|
||||
}
|
||||
|
||||
y = z - y;
|
||||
S = 0.0F;
|
||||
for (k = 0; k < 3; k++) {
|
||||
S += K[k] * C[k];
|
||||
}
|
||||
|
||||
S += R;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (k = 0; k < 3; k++) {
|
||||
f0 += P_apriori[i0 + 3 * k] * C[k];
|
||||
}
|
||||
|
||||
K[i0] = f0 / S;
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
x_aposteriori[i0] += K[i0] * y;
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 9; i0++) {
|
||||
I[i0] = 0;
|
||||
}
|
||||
|
||||
for (k = 0; k < 3; k++) {
|
||||
I[k + 3 * k] = 1;
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
b_A[k + 3 * i0] = (real32_T)I[k + 3 * i0] - K[k] * C[i0];
|
||||
}
|
||||
}
|
||||
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
for (k = 0; k < 3; k++) {
|
||||
P_aposteriori[i0 + 3 * k] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
P_aposteriori[i0 + 3 * k] += b_A[i0 + 3 * i1] * P_apriori[i1 + 3 * k];
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i0 = 0; i0 < 9; i0++) {
|
||||
P_aposteriori[i0] = P_apriori[i0];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_H__
|
||||
#define __POSITIONKALMANFILTER1D_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D(const real32_T A[9], const real32_T B[3], const real32_T C[3], const real32_T x_aposteriori_k[3], const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T Q[9], real32_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3], real32_T P_aposteriori[9]);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D.h) */
|
||||
@@ -0,0 +1,157 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D_dT.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D_dT(real32_T dT, const real32_T x_aposteriori_k[3],
|
||||
const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update,
|
||||
const real32_T Q[9], real_T R, real32_T thresh, real32_T decay, real32_T
|
||||
x_aposteriori[3], real32_T P_aposteriori[9])
|
||||
{
|
||||
real32_T A[9];
|
||||
int32_T i;
|
||||
static const int8_T iv0[3] = { 0, 0, 1 };
|
||||
|
||||
real32_T K[3];
|
||||
real32_T f0;
|
||||
int32_T i0;
|
||||
real32_T b_A[9];
|
||||
int32_T i1;
|
||||
real32_T P_apriori[9];
|
||||
static const int8_T iv1[3] = { 1, 0, 0 };
|
||||
|
||||
real32_T fv0[3];
|
||||
real32_T y;
|
||||
static const int8_T iv2[3] = { 1, 0, 0 };
|
||||
|
||||
real32_T S;
|
||||
int8_T I[9];
|
||||
|
||||
/* dynamics */
|
||||
A[0] = 1.0F;
|
||||
A[3] = dT;
|
||||
A[6] = -0.5F * dT * dT;
|
||||
A[1] = 0.0F;
|
||||
A[4] = 1.0F;
|
||||
A[7] = -dT;
|
||||
for (i = 0; i < 3; i++) {
|
||||
A[2 + 3 * i] = (real32_T)iv0[i];
|
||||
}
|
||||
|
||||
/* prediction */
|
||||
K[0] = 0.5F * dT * dT;
|
||||
K[1] = dT;
|
||||
K[2] = 0.0F;
|
||||
for (i = 0; i < 3; i++) {
|
||||
f0 = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 += A[i + 3 * i0] * x_aposteriori_k[i0];
|
||||
}
|
||||
|
||||
x_aposteriori[i] = f0 + K[i] * u;
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
b_A[i + 3 * i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
b_A[i + 3 * i0] += A[i + 3 * i1] * P_aposteriori_k[i1 + 3 * i0];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
f0 += b_A[i + 3 * i1] * A[i0 + 3 * i1];
|
||||
}
|
||||
|
||||
P_apriori[i + 3 * i0] = f0 + Q[i + 3 * i0];
|
||||
}
|
||||
}
|
||||
|
||||
if ((real32_T)fabs(u) < thresh) {
|
||||
x_aposteriori[1] *= decay;
|
||||
}
|
||||
|
||||
/* update */
|
||||
if (gps_update == 1) {
|
||||
f0 = 0.0F;
|
||||
for (i = 0; i < 3; i++) {
|
||||
f0 += (real32_T)iv1[i] * x_aposteriori[i];
|
||||
fv0[i] = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
fv0[i] += (real32_T)iv1[i0] * P_apriori[i0 + 3 * i];
|
||||
}
|
||||
}
|
||||
|
||||
y = z - f0;
|
||||
f0 = 0.0F;
|
||||
for (i = 0; i < 3; i++) {
|
||||
f0 += fv0[i] * (real32_T)iv2[i];
|
||||
}
|
||||
|
||||
S = f0 + (real32_T)R;
|
||||
for (i = 0; i < 3; i++) {
|
||||
f0 = 0.0F;
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
f0 += P_apriori[i + 3 * i0] * (real32_T)iv2[i0];
|
||||
}
|
||||
|
||||
K[i] = f0 / S;
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
x_aposteriori[i] += K[i] * y;
|
||||
}
|
||||
|
||||
for (i = 0; i < 9; i++) {
|
||||
I[i] = 0;
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
I[i + 3 * i] = 1;
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
A[i0 + 3 * i] = (real32_T)I[i0 + 3 * i] - K[i0] * (real32_T)iv1[i];
|
||||
}
|
||||
}
|
||||
|
||||
for (i = 0; i < 3; i++) {
|
||||
for (i0 = 0; i0 < 3; i0++) {
|
||||
P_aposteriori[i + 3 * i0] = 0.0F;
|
||||
for (i1 = 0; i1 < 3; i1++) {
|
||||
P_aposteriori[i + 3 * i0] += A[i + 3 * i1] * P_apriori[i1 + 3 * i0];
|
||||
}
|
||||
}
|
||||
}
|
||||
} else {
|
||||
for (i = 0; i < 9; i++) {
|
||||
P_aposteriori[i] = P_apriori[i];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D_dT.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_DT_H__
|
||||
#define __POSITIONKALMANFILTER1D_DT_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_dT_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D_dT(real32_T dT, const real32_T x_aposteriori_k[3], const real32_T P_aposteriori_k[9], real32_T u, real32_T z, uint8_T gps_update, const real32_T Q[9], real_T R, real32_T thresh, real32_T decay, real32_T x_aposteriori[3], real32_T P_aposteriori[9]);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_dT.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT_initialize.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT_initialize'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D_dT.h"
|
||||
#include "positionKalmanFilter1D_dT_initialize.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D_dT_initialize(void)
|
||||
{
|
||||
rt_InitInfAndNaN(8U);
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D_dT_initialize.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT_initialize.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT_initialize'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_DT_INITIALIZE_H__
|
||||
#define __POSITIONKALMANFILTER1D_DT_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_dT_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D_dT_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_dT_initialize.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT_terminate.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT_terminate'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D_dT.h"
|
||||
#include "positionKalmanFilter1D_dT_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D_dT_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D_dT_terminate.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT_terminate.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT_terminate'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_DT_TERMINATE_H__
|
||||
#define __POSITIONKALMANFILTER1D_DT_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_dT_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D_dT_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_dT_terminate.h) */
|
||||
@@ -0,0 +1,16 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_dT_types.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_dT'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 17:37:33 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_DT_TYPES_H__
|
||||
#define __POSITIONKALMANFILTER1D_DT_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_dT_types.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_initialize.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_initialize'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D.h"
|
||||
#include "positionKalmanFilter1D_initialize.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D_initialize(void)
|
||||
{
|
||||
rt_InitInfAndNaN(8U);
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D_initialize.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_initialize.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_initialize'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_INITIALIZE_H__
|
||||
#define __POSITIONKALMANFILTER1D_INITIALIZE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D_initialize(void);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_initialize.h) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_terminate.c
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_terminate'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
/* Include files */
|
||||
#include "rt_nonfinite.h"
|
||||
#include "positionKalmanFilter1D.h"
|
||||
#include "positionKalmanFilter1D_terminate.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
|
||||
/* Function Definitions */
|
||||
void positionKalmanFilter1D_terminate(void)
|
||||
{
|
||||
/* (no terminate code required) */
|
||||
}
|
||||
|
||||
/* End of code generation (positionKalmanFilter1D_terminate.c) */
|
||||
@@ -0,0 +1,31 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_terminate.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D_terminate'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_TERMINATE_H__
|
||||
#define __POSITIONKALMANFILTER1D_TERMINATE_H__
|
||||
/* Include files */
|
||||
#include <math.h>
|
||||
#include <stddef.h>
|
||||
#include <stdlib.h>
|
||||
|
||||
#include "rtwtypes.h"
|
||||
#include "positionKalmanFilter1D_types.h"
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
/* Named Constants */
|
||||
|
||||
/* Variable Declarations */
|
||||
|
||||
/* Variable Definitions */
|
||||
|
||||
/* Function Declarations */
|
||||
extern void positionKalmanFilter1D_terminate(void);
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_terminate.h) */
|
||||
@@ -0,0 +1,16 @@
|
||||
/*
|
||||
* positionKalmanFilter1D_types.h
|
||||
*
|
||||
* Code generation for function 'positionKalmanFilter1D'
|
||||
*
|
||||
* C source code generated on: Fri Nov 30 14:26:11 2012
|
||||
*
|
||||
*/
|
||||
|
||||
#ifndef __POSITIONKALMANFILTER1D_TYPES_H__
|
||||
#define __POSITIONKALMANFILTER1D_TYPES_H__
|
||||
|
||||
/* Type Definitions */
|
||||
|
||||
#endif
|
||||
/* End of code generation (positionKalmanFilter1D_types.h) */
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user