From b23af6108772f8049ca94dfd8c648e1014917062 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:47:35 +0100 Subject: [PATCH 01/87] System disables all driver publications it can get hold of once entering HIL --- .../commander/state_machine_helper.cpp | 31 +++++++++++++++++++ 1 file changed, 31 insertions(+) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 490fc8fc6b..44e3aa787f 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -42,6 +42,8 @@ #include #include #include +#include +#include #include #include @@ -51,6 +53,7 @@ #include #include #include +#include #include #include "state_machine_helper.h" @@ -491,6 +494,34 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s current_control_mode->flag_system_hil_enabled = true; mavlink_log_critical(mavlink_fd, "Switched to ON hil state"); valid_transition = true; + + // Disable publication of all attached sensors + + /* list directory */ + DIR *d; + struct dirent *direntry; + d = opendir("/dev"); + if (d) { + + while ((direntry = readdir(d)) != NULL) { + + bool blocked = false; + int sensfd = ::open(direntry->d_name, 0); + ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0); + close(sensfd); + + printf("Disabling %s\n: %s", direntry->d_name, (blocked) ? "OK" : "FAIL"); + } + + closedir(d); + + warnx("directory listing ok (FS mounted and readable)"); + + } else { + /* failed opening dir */ + warnx("FAILED LISTING DEVICE ROOT DIRECTORY"); + return 1; + } } break; From c6e196edca7acae0b548a85c94d0c8f37df3c7aa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:52:19 +0100 Subject: [PATCH 02/87] Support disabling GPS output via IOCTL, general cleanup of author and copyright code style --- src/drivers/gps/gps.cpp | 21 +++++++++++++-------- src/drivers/gps/gps_helper.cpp | 7 ++++--- src/drivers/gps/gps_helper.h | 6 +++--- src/drivers/gps/module.mk | 2 +- src/drivers/gps/mtk.cpp | 11 +++++++---- src/drivers/gps/mtk.h | 11 +++++++---- src/drivers/gps/ubx.cpp | 10 ++++++---- src/drivers/gps/ubx.h | 17 ++++++++++++----- 8 files changed, 53 insertions(+), 32 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 6b72d560fa..a736cbdf6b 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -289,11 +289,13 @@ GPS::task_main() //no time and satellite information simulated - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + if (!(_pub_blocked)) { + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); - } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } } usleep(2e5); @@ -330,11 +332,14 @@ GPS::task_main() while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) { // lock(); /* opportunistic publishing - else invalid data would end up on the bus */ - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); - } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + if (!(_pub_blocked)) { + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } } last_rate_count++; diff --git a/src/drivers/gps/gps_helper.cpp b/src/drivers/gps/gps_helper.cpp index 2e2cbc8ddf..2360ff39bd 100644 --- a/src/drivers/gps/gps_helper.cpp +++ b/src/drivers/gps/gps_helper.cpp @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2012-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 @@ -41,6 +39,9 @@ /** * @file gps_helper.cpp + * + * @author Thomas Gubler + * @author Julian Oes */ float diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h index 73d4b889cb..cfb9e0d43d 100644 --- a/src/drivers/gps/gps_helper.h +++ b/src/drivers/gps/gps_helper.h @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2012-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 @@ -35,6 +33,8 @@ /** * @file gps_helper.h + * @author Thomas Gubler + * @author Julian Oes */ #ifndef GPS_HELPER_H diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk index 097db2abfc..82c67d40a3 100644 --- a/src/drivers/gps/module.mk +++ b/src/drivers/gps/module.mk @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. +# Copyright (c) 2012-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 diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp index 56b702ea6c..456a9645bf 100644 --- a/src/drivers/gps/mtk.cpp +++ b/src/drivers/gps/mtk.cpp @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,7 +31,12 @@ * ****************************************************************************/ -/* @file mkt.cpp */ +/** + * @file mkt.cpp + * + * @author Thomas Gubler + * @author Julian Oes + */ #include #include diff --git a/src/drivers/gps/mtk.h b/src/drivers/gps/mtk.h index b5cfbf0a6d..9032e45b03 100644 --- a/src/drivers/gps/mtk.h +++ b/src/drivers/gps/mtk.h @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,7 +31,12 @@ * ****************************************************************************/ -/* @file mtk.h */ +/** + * @file mkt.cpp + * + * @author Thomas Gubler + * @author Julian Oes + */ #ifndef MTK_H_ #define MTK_H_ diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 86291901cb..8a2afecb7e 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -1,9 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes - * Anton Babushkin + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -40,8 +37,13 @@ * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description * including Prototol Specification. * + * @author Thomas Gubler + * @author Julian Oes + * @author Anton Babushkin + * * @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf */ + #include #include #include diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 76ef873a36..79a904f4a4 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -1,9 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2008-2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes - * Anton Babushkin + * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,7 +31,17 @@ * ****************************************************************************/ -/* @file U-Blox protocol definitions */ +/** + * @file ubx.h + * + * U-Blox protocol definition. Following u-blox 6/7 Receiver Description + * including Prototol Specification. + * + * @author Thomas Gubler + * @author Julian Oes + * @author Anton Babushkin + * + */ #ifndef UBX_H_ #define UBX_H_ From 9bf512cac82815e690774ddfc2fdeda29c22f4a0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:52:41 +0100 Subject: [PATCH 03/87] Framework to support disabling publications via IOCTL --- src/drivers/device/cdev.cpp | 11 ++++++++++- src/drivers/device/device.cpp | 2 +- src/drivers/device/device.h | 4 +++- 3 files changed, 14 insertions(+), 3 deletions(-) diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp index 7954ce5ab5..65a9705f55 100644 --- a/src/drivers/device/cdev.cpp +++ b/src/drivers/device/cdev.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -38,6 +38,7 @@ */ #include "device.h" +#include "drivers/drv_device.h" #include #include @@ -93,6 +94,7 @@ CDev::CDev(const char *name, Device(name, irq), // public // protected + _pub_blocked(false), // private _devname(devname), _registered(false), @@ -256,6 +258,13 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg) case DIOC_GETPRIV: *(void **)(uintptr_t)arg = (void *)this; return OK; + break; + case DEVIOCSPUBBLOCK: + _pub_blocked = (arg != 0); + break; + case DEVIOCGPUBBLOCK: + return _pub_blocked; + break; } return -ENOTTY; diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp index c3ee77b1ca..6834551493 100644 --- a/src/drivers/device/device.cpp +++ b/src/drivers/device/device.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index 0235f62844..d99f229220 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -415,6 +415,8 @@ protected: */ virtual int unregister_class_devname(const char *class_devname, unsigned class_instance); + bool _pub_blocked; /**< true if publishing should be blocked */ + private: static const unsigned _max_pollwaiters = 8; From d72c82f66bf6dac8e6d10bf1024641908d3b854c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:53:15 +0100 Subject: [PATCH 04/87] Airspeed does not publish if disabled --- src/drivers/airspeed/airspeed.cpp | 12 +++++++----- src/drivers/airspeed/airspeed.h | 4 +++- src/drivers/ets_airspeed/ets_airspeed.cpp | 15 +++++++++++++-- src/drivers/meas_airspeed/meas_airspeed.cpp | 15 +++++++++++++-- 4 files changed, 36 insertions(+), 10 deletions(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 5e45cc936c..215d3792e8 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -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 @@ -86,6 +86,7 @@ Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) : _collect_phase(false), _diff_pres_offset(0.0f), _airspeed_pub(-1), + _class_instance(-1), _conversion_interval(conversion_interval), _sample_perf(perf_alloc(PC_ELAPSED, "airspeed_read")), _comms_errors(perf_alloc(PC_COUNT, "airspeed_comms_errors")) @@ -102,6 +103,9 @@ Airspeed::~Airspeed() /* make sure we are truly inactive */ stop(); + if (_class_instance != -1) + unregister_class_devname(AIRSPEED_DEVICE_PATH, _class_instance); + /* free any existing reports */ if (_reports != nullptr) delete _reports; @@ -126,10 +130,8 @@ Airspeed::init() if (_reports == nullptr) goto out; - /* get a publish handle on the airspeed topic */ - differential_pressure_s zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &zero_report); + /* register alternate interfaces if we have to */ + _class_instance = register_class_devname(AIRSPEED_DEVICE_PATH); if (_airspeed_pub < 0) warnx("failed to create airspeed sensor object. Did you start uOrb?"); diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h index c341aa2c6d..c27b1bcd80 100644 --- a/src/drivers/airspeed/airspeed.h +++ b/src/drivers/airspeed/airspeed.h @@ -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 @@ -127,6 +127,8 @@ protected: orb_advert_t _airspeed_pub; + int _class_instance; + unsigned _conversion_interval; perf_counter_t _sample_perf; diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index de371bf324..cdc70ac37c 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -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 @@ -185,7 +185,18 @@ ETSAirspeed::collect() report.max_differential_pressure_pa = _max_differential_pressure_pa; /* announce the airspeed if needed, just publish else */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_airspeed_pub > 0) { + /* publish it */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); + } else { + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &report); + + if (_airspeed_pub < 0) + debug("failed to create differential_pressure publication"); + } + } new_report(report); diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index a95c4576b0..fee13f139c 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -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 @@ -217,7 +217,18 @@ MEASAirspeed::collect() report.max_differential_pressure_pa = _max_differential_pressure_pa; /* announce the airspeed if needed, just publish else */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_airspeed_pub > 0) { + /* publish it */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); + } else { + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &report); + + if (_airspeed_pub < 0) + debug("failed to create differential_pressure publication"); + } + } new_report(report); From c7e2841baa98bb985b402c89bef85e56f765ec11 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:53:31 +0100 Subject: [PATCH 05/87] BMA180 does not publish if disabled --- src/drivers/bma180/bma180.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp index 1590cc182b..df4e8f9989 100644 --- a/src/drivers/bma180/bma180.cpp +++ b/src/drivers/bma180/bma180.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -723,7 +723,8 @@ BMA180::measure() poll_notify(POLLIN); /* publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &report); + if !(_pub_blocked) + orb_publish(ORB_ID(sensor_accel), _accel_topic, &report); /* stop the perf counter */ perf_end(_sample_perf); From 28a3dc726f8e4f3696736798a1d92bf7d9de6100 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:53:56 +0100 Subject: [PATCH 06/87] Support for publication blocking: HMC5883 --- src/drivers/hmc5883/hmc5883.cpp | 37 +++++++++++++++++---------------- 1 file changed, 19 insertions(+), 18 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index d3b99ae66e..49b72cf794 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -381,16 +381,6 @@ HMC5883::init() reset(); _class_instance = register_class_devname(MAG_DEVICE_PATH); - if (_class_instance == CLASS_DEVICE_PRIMARY) { - /* get a publish handle on the mag topic if we are - * the primary mag */ - struct mag_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _mag_topic = orb_advertise(ORB_ID(sensor_mag), &zero_report); - - if (_mag_topic < 0) - debug("failed to create sensor_mag object"); - } ret = OK; /* sensor is ok, but not calibrated */ @@ -885,9 +875,18 @@ HMC5883::collect() } #endif - if (_mag_topic != -1) { - /* publish it */ - orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_mag_topic != -1) { + /* publish it */ + orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report); + } else { + _mag_topic = orb_advertise(ORB_ID(sensor_mag), &new_report); + + if (_mag_topic < 0) + debug("failed to create sensor_mag publication"); + } + } /* post a report to the ring */ @@ -1134,10 +1133,12 @@ int HMC5883::check_calibration() SUBSYSTEM_TYPE_MAG}; 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); + if (!(_pub_blocked)) { + if (pub > 0) { + orb_publish(ORB_ID(subsystem_info), pub, &info); + } else { + pub = orb_advertise(ORB_ID(subsystem_info), &info); + } } } From 3c7766db6c58dea67b66263d2a7c01bb57177db5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:54:10 +0100 Subject: [PATCH 07/87] Support for publication blocking: L3GD20(H) --- src/drivers/l3gd20/l3gd20.cpp | 23 ++++++++++++++--------- 1 file changed, 14 insertions(+), 9 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 670e51b979..e885b1bf9e 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -379,12 +379,6 @@ L3GD20::init() goto out; _class_instance = register_class_devname(GYRO_DEVICE_PATH); - if (_class_instance == CLASS_DEVICE_PRIMARY) { - /* advertise sensor topic */ - struct gyro_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &zero_report); - } reset(); @@ -894,8 +888,19 @@ L3GD20::measure() poll_notify(POLLIN); /* publish for subscribers */ - if (_gyro_topic > 0) - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_gyro_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report); + } else { + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &report); + + if (_gyro_topic < 0) + debug("failed to create sensor_gyro publication"); + } + + } _read++; From a34a14ce862c270192283514d8a1914fbe43bd48 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:54:25 +0100 Subject: [PATCH 08/87] Support for publication blocking: LSM303D, cleaned up device start --- src/drivers/lsm303d/lsm303d.cpp | 64 +++++++++++++++++---------------- 1 file changed, 34 insertions(+), 30 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 969b5e25f9..3bd7a66f6b 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -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 @@ -277,15 +277,15 @@ private: unsigned _mag_samplerate; orb_advert_t _accel_topic; - int _class_instance; + int _accel_class_instance; unsigned _accel_read; unsigned _mag_read; perf_counter_t _accel_sample_perf; perf_counter_t _mag_sample_perf; - perf_counter_t _reg7_resets; perf_counter_t _reg1_resets; + perf_counter_t _reg7_resets; perf_counter_t _extreme_values; perf_counter_t _accel_reschedules; @@ -295,8 +295,8 @@ private: // expceted values of reg1 and reg7 to catch in-flight // brownouts of the sensor - uint8_t _reg7_expected; uint8_t _reg1_expected; + uint8_t _reg7_expected; // accel logging int _accel_log_fd; @@ -500,7 +500,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) : _mag_range_scale(0.0f), _mag_samplerate(0), _accel_topic(-1), - _class_instance(-1), + _accel_class_instance(-1), _accel_read(0), _mag_read(0), _accel_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d_accel_read")), @@ -551,8 +551,8 @@ LSM303D::~LSM303D() if (_mag_reports != nullptr) delete _mag_reports; - if (_class_instance != -1) - unregister_class_devname(ACCEL_DEVICE_PATH, _class_instance); + if (_accel_class_instance != -1) + unregister_class_devname(ACCEL_DEVICE_PATH, _accel_class_instance); delete _mag; @@ -562,13 +562,13 @@ LSM303D::~LSM303D() perf_free(_reg1_resets); perf_free(_reg7_resets); perf_free(_extreme_values); + perf_free(_accel_reschedules); } int LSM303D::init() { int ret = ERROR; - int mag_ret; /* do SPI init (and probe) first */ if (SPI::init() != OK) { @@ -597,14 +597,7 @@ LSM303D::init() goto out; } - _class_instance = register_class_devname(ACCEL_DEVICE_PATH); - if (_class_instance == CLASS_DEVICE_PRIMARY) { - // we are the primary accel device, so advertise to - // the ORB - struct accel_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &zero_report); - } + _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); out: return ret; @@ -727,7 +720,7 @@ LSM303D::check_extremes(const accel_report *arb) _last_log_us = now; ::dprintf(_accel_log_fd, "ARB %llu %.3f %.3f %.3f %d %d %d boot_ok=%u\r\n", (unsigned long long)arb->timestamp, - arb->x, arb->y, arb->z, + (double)arb->x, (double)arb->y, (double)arb->z, (int)arb->x_raw, (int)arb->y_raw, (int)arb->z_raw, @@ -1517,9 +1510,18 @@ LSM303D::measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_accel_topic != -1) { - /* publish for subscribers */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); + if (_accel_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_accel_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); + } else { + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &accel_report); + + if (_accel_topic < 0) + debug("failed to create sensor_accel publication"); + } + } _accel_read++; @@ -1591,9 +1593,18 @@ LSM303D::mag_measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_mag->_mag_topic != -1) { - /* publish for subscribers */ - orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report); + if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_mag->_mag_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report); + } else { + _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mag_report); + + if (_mag->_mag_topic < 0) + debug("failed to create sensor_mag publication"); + } + } _mag_read++; @@ -1707,13 +1718,6 @@ LSM303D_mag::init() goto out; _mag_class_instance = register_class_devname(MAG_DEVICE_PATH); - if (_mag_class_instance == CLASS_DEVICE_PRIMARY) { - // we are the primary mag device, so advertise to - // the ORB - struct mag_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _mag_topic = orb_advertise(ORB_ID(sensor_mag), &zero_report); - } out: return ret; From 7af62bbe9e4baaa846a37176d6942e1893e42715 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:54:38 +0100 Subject: [PATCH 09/87] Support for publication blocking: MPU6000, cleaned up device start --- src/drivers/mpu6000/mpu6000.cpp | 46 +++++++++++++++++++-------------- 1 file changed, 26 insertions(+), 20 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index bbc595af46..02fe6df4a1 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -443,7 +443,6 @@ int MPU6000::init() { int ret; - int gyro_ret; /* do SPI init (and probe) first */ ret = SPI::init(); @@ -488,16 +487,7 @@ MPU6000::init() return ret; } - /* fetch an initial set of measurements for advertisement */ - measure(); - _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); - if (_accel_class_instance == CLASS_DEVICE_PRIMARY) { - /* advertise accel topic */ - accel_report ar; - _accel_reports->get(&ar); - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &ar); - } out: return ret; @@ -1307,11 +1297,32 @@ MPU6000::measure() poll_notify(POLLIN); _gyro->parent_poll_notify(); - if (_accel_topic != -1) { - orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); + if (_accel_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_accel_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); + } else { + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arb); + + if (_accel_topic < 0) + debug("failed to create sensor_accel publication"); + } + } - if (_gyro->_gyro_topic != -1) { - orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); + + if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_gyro->_gyro_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); + } else { + _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grb); + + if (_gyro->_gyro_topic < 0) + debug("failed to create sensor_gyro publication"); + } + } /* stop measuring */ @@ -1356,11 +1367,6 @@ MPU6000_gyro::init() } _gyro_class_instance = register_class_devname(GYRO_DEVICE_PATH); - if (_gyro_class_instance == CLASS_DEVICE_PRIMARY) { - gyro_report gr; - memset(&gr, 0, sizeof(gr)); - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &gr); - } out: return ret; From e6a67b1deb0e7d5b315d3c570ff010de4d54b65f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:54:55 +0100 Subject: [PATCH 10/87] Support for publication blocking: MS5611, cleaned up device start --- src/drivers/ms5611/ms5611.cpp | 33 +++++++++++++++++++++------------ 1 file changed, 21 insertions(+), 12 deletions(-) diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 6326cf7fcb..0893315667 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012-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 @@ -132,6 +132,8 @@ protected: orb_advert_t _baro_topic; + int _class_instance; + perf_counter_t _sample_perf; perf_counter_t _measure_perf; perf_counter_t _comms_errors; @@ -204,6 +206,7 @@ MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf) : _SENS(0), _msl_pressure(101325), _baro_topic(-1), + _class_instance(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")), _measure_perf(perf_alloc(PC_ELAPSED, "ms5611_measure")), _comms_errors(perf_alloc(PC_COUNT, "ms5611_comms_errors")), @@ -218,6 +221,9 @@ MS5611::~MS5611() /* make sure we are truly inactive */ stop_cycle(); + if (_class_instance != -1) + unregister_class_devname(BARO_DEVICE_PATH, _class_instance); + /* free any existing reports */ if (_reports != nullptr) delete _reports; @@ -251,16 +257,8 @@ MS5611::init() goto out; } - /* get a publish handle on the baro topic */ - struct baro_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _baro_topic = orb_advertise(ORB_ID(sensor_baro), &zero_report); - - if (_baro_topic < 0) { - debug("failed to create sensor_baro object"); - ret = -ENOSPC; - goto out; - } + /* register alternate interfaces if we have to */ + _class_instance = register_class_devname(BARO_DEVICE_PATH); ret = OK; out: @@ -670,7 +668,18 @@ MS5611::collect() report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a; /* publish it */ - orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + + if (_baro_topic > 0) { + /* publish it */ + orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); + } else { + _baro_topic = orb_advertise(ORB_ID(sensor_baro), &report); + + if (_baro_topic < 0) + debug("failed to create sensor_baro publication"); + } + } if (_reports->force(&report)) { perf_count(_buffer_overflows); From dbbe4ab1d587376bc2d530b3e80a001aa30b69c7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 12 Jan 2014 11:55:16 +0100 Subject: [PATCH 11/87] Header for publication disable --- src/drivers/drv_device.h | 62 ++++++++++++++++++++++++++++++++++++++++ 1 file changed, 62 insertions(+) create mode 100644 src/drivers/drv_device.h diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h new file mode 100644 index 0000000000..b310beb746 --- /dev/null +++ b/src/drivers/drv_device.h @@ -0,0 +1,62 @@ +/**************************************************************************** + * + * 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 + * 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 drv_device.h + * + * Generic device / sensor interface. + */ + +#ifndef _DRV_DEVICE_H +#define _DRV_DEVICE_H + +#include +#include + +#include "drv_sensor.h" +#include "drv_orb_dev.h" + +/* + * ioctl() definitions + */ + +#define _DEVICEIOCBASE (0x100) +#define _DEVICEIOC(_n) (_IOC(_DEVICEIOCBASE, _n)) + +/** ask device to stop publishing */ +#define DEVIOCSPUBBLOCK _DEVICEIOC(0) + +/** check publication block status */ +#define DEVIOCGPUBBLOCK _DEVICEIOC(1) + +#endif /* _DRV_DEVICE_H */ From 47e0c926a6932b7a60ce85a5c748ce5bfcc102e7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 14:02:16 +0100 Subject: [PATCH 12/87] Fixed two typos identified by kroimon --- src/drivers/gps/mtk.cpp | 2 +- src/drivers/gps/mtk.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp index 456a9645bf..c90ecbe281 100644 --- a/src/drivers/gps/mtk.cpp +++ b/src/drivers/gps/mtk.cpp @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file mkt.cpp + * @file mtk.cpp * * @author Thomas Gubler * @author Julian Oes diff --git a/src/drivers/gps/mtk.h b/src/drivers/gps/mtk.h index 9032e45b03..a2d5e27bbf 100644 --- a/src/drivers/gps/mtk.h +++ b/src/drivers/gps/mtk.h @@ -32,7 +32,7 @@ ****************************************************************************/ /** - * @file mkt.cpp + * @file mtk.cpp * * @author Thomas Gubler * @author Julian Oes From c4dc310ebda8f79ec13c68745408444661b32fe1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 14:03:57 +0100 Subject: [PATCH 13/87] Fixed bogus return value of publication blocking disable --- src/modules/commander/state_machine_helper.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 44e3aa787f..7ae61d9ef2 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -505,12 +505,11 @@ int hil_state_transition(hil_state_t new_state, int status_pub, struct vehicle_s while ((direntry = readdir(d)) != NULL) { - bool blocked = false; int sensfd = ::open(direntry->d_name, 0); - ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0); + int block_ret = ::ioctl(sensfd, DEVIOCSPUBBLOCK, 0); close(sensfd); - printf("Disabling %s\n: %s", direntry->d_name, (blocked) ? "OK" : "FAIL"); + printf("Disabling %s\n: %s", direntry->d_name, (!block_ret) ? "OK" : "FAIL"); } closedir(d); From d19971065140bdfbbe5972f2a394597504abef9e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 15:40:46 +0100 Subject: [PATCH 14/87] Fixed up init sequence of all sensors - we can publish in interrupt context, but not advertise! All advertisements now contain valid data --- src/drivers/airspeed/airspeed.cpp | 16 ++++- src/drivers/bma180/bma180.cpp | 22 ++++-- src/drivers/ets_airspeed/ets_airspeed.cpp | 15 +--- src/drivers/l3gd20/l3gd20.cpp | 30 ++++---- src/drivers/lsm303d/lsm303d.cpp | 61 +++++++++------- src/drivers/meas_airspeed/meas_airspeed.cpp | 15 +--- src/drivers/mpu6000/mpu6000.cpp | 59 ++++++++------- src/drivers/ms5611/ms5611.cpp | 80 +++++++++++++++------ 8 files changed, 186 insertions(+), 112 deletions(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 215d3792e8..71c0b70f01 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -133,8 +133,20 @@ Airspeed::init() /* register alternate interfaces if we have to */ _class_instance = register_class_devname(AIRSPEED_DEVICE_PATH); - if (_airspeed_pub < 0) - warnx("failed to create airspeed sensor object. Did you start uOrb?"); + /* publication init */ + if (_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct differential_pressure_s arp; + measure(); + _reports->get(&arp); + + /* measurement will have generated a report, publish */ + _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp); + + if (_airspeed_pub < 0) + warnx("failed to create airspeed sensor object. uORB started?"); + } ret = OK; /* sensor is ok, but we don't really know if it is within range */ diff --git a/src/drivers/bma180/bma180.cpp b/src/drivers/bma180/bma180.cpp index df4e8f9989..e43a348052 100644 --- a/src/drivers/bma180/bma180.cpp +++ b/src/drivers/bma180/bma180.cpp @@ -153,6 +153,7 @@ private: float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; + int _class_instance; unsigned _current_lowpass; unsigned _current_range; @@ -238,6 +239,7 @@ BMA180::BMA180(int bus, spi_dev_e device) : _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), + _class_instance(-1), _current_lowpass(0), _current_range(0), _sample_perf(perf_alloc(PC_ELAPSED, "bma180_read")) @@ -282,11 +284,6 @@ BMA180::init() if (_reports == nullptr) goto out; - /* advertise sensor topic */ - struct accel_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &zero_report); - /* perform soft reset (p48) */ write_reg(ADDR_RESET, SOFT_RESET); @@ -322,6 +319,19 @@ BMA180::init() ret = ERROR; } + _class_instance = register_class_devname(ACCEL_DEVICE_PATH); + + /* advertise sensor topic, measure manually to initialize valid report */ + measure(); + + if (_class_instance == CLASS_DEVICE_PRIMARY) { + struct accel_report arp; + _reports->get(&arp); + + /* measurement will have generated a report, publish */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp); + } + out: return ret; } @@ -723,7 +733,7 @@ BMA180::measure() poll_notify(POLLIN); /* publish for subscribers */ - if !(_pub_blocked) + if (_accel_topic > 0 && !(_pub_blocked)) orb_publish(ORB_ID(sensor_accel), _accel_topic, &report); /* stop the perf counter */ diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index cdc70ac37c..8bbef5cfa0 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -184,18 +184,9 @@ ETSAirspeed::collect() report.voltage = 0; report.max_differential_pressure_pa = _max_differential_pressure_pa; - /* announce the airspeed if needed, just publish else */ - if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_airspeed_pub > 0) { - /* publish it */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); - } else { - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &report); - - if (_airspeed_pub < 0) - debug("failed to create differential_pressure publication"); - } + if (_airspeed_pub > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); } new_report(report); diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index e885b1bf9e..90c3db9ae9 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -382,6 +382,21 @@ L3GD20::init() reset(); + measure(); + + if (_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct gyro_report grp; + _reports->get(&grp); + + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp); + + if (_gyro_topic < 0) + debug("failed to create sensor_gyro publication"); + + } + ret = OK; out: return ret; @@ -888,18 +903,9 @@ L3GD20::measure() poll_notify(POLLIN); /* publish for subscribers */ - if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_gyro_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report); - } else { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &report); - - if (_gyro_topic < 0) - debug("failed to create sensor_gyro publication"); - } - + if (_gyro_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report); } _read++; diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 3bd7a66f6b..4dee7649bc 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -597,8 +597,39 @@ LSM303D::init() goto out; } + /* fill report structures */ + measure(); + + if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct mag_report mrp; + _mag_reports->get(&mrp); + + /* measurement will have generated a report, publish */ + _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mrp); + + if (_mag->_mag_topic < 0) + debug("failed to create sensor_mag publication"); + + } + _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); + if (_accel_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct accel_report arp; + _accel_reports->get(&arp); + + /* measurement will have generated a report, publish */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp); + + if (_accel_topic < 0) + debug("failed to create sensor_accel publication"); + + } + out: return ret; } @@ -1510,18 +1541,9 @@ LSM303D::measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_accel_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_accel_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); - } else { - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &accel_report); - - if (_accel_topic < 0) - debug("failed to create sensor_accel publication"); - } - + if (_accel_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); } _accel_read++; @@ -1593,18 +1615,9 @@ LSM303D::mag_measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_mag->_mag_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report); - } else { - _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mag_report); - - if (_mag->_mag_topic < 0) - debug("failed to create sensor_mag publication"); - } - + if (_mag->_mag_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report); } _mag_read++; diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index fee13f139c..51a059e394 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -216,18 +216,9 @@ MEASAirspeed::collect() report.voltage = 0; report.max_differential_pressure_pa = _max_differential_pressure_pa; - /* announce the airspeed if needed, just publish else */ - if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_airspeed_pub > 0) { - /* publish it */ - orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); - } else { - _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &report); - - if (_airspeed_pub < 0) - debug("failed to create differential_pressure publication"); - } + if (_airspeed_pub > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(differential_pressure), _airspeed_pub, &report); } new_report(report); diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 02fe6df4a1..bf80c9cff2 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -489,6 +489,35 @@ MPU6000::init() _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); + measure(); + + if (_accel_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct accel_report arp; + _accel_reports->get(&arp); + + /* measurement will have generated a report, publish */ + _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp); + + if (_accel_topic < 0) + debug("failed to create sensor_accel publication"); + + } + + if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY) { + + /* advertise sensor topic, measure manually to initialize valid report */ + struct gyro_report grp; + _gyro_reports->get(&grp); + + _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp); + + if (_gyro->_gyro_topic < 0) + debug("failed to create sensor_gyro publication"); + + } + out: return ret; } @@ -1297,32 +1326,14 @@ MPU6000::measure() poll_notify(POLLIN); _gyro->parent_poll_notify(); - if (_accel_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_accel_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); - } else { - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arb); - - if (_accel_topic < 0) - debug("failed to create sensor_accel publication"); - } - + if (_accel_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); } - if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_gyro->_gyro_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); - } else { - _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grb); - - if (_gyro->_gyro_topic < 0) - debug("failed to create sensor_gyro publication"); - } - + if (_gyro->_gyro_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); } /* stop measuring */ diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 0893315667..0ef056273f 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -90,6 +90,7 @@ static const int ERROR = -1; /* internal conversion time: 9.17 ms, so should not be read at rates higher than 100 Hz */ #define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */ #define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */ +#define MS5611_BARO_DEVICE_PATH "/dev/ms5611" class MS5611 : public device::CDev { @@ -194,7 +195,7 @@ protected: extern "C" __EXPORT int ms5611_main(int argc, char *argv[]); MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf) : - CDev("MS5611", BARO_DEVICE_PATH), + CDev("MS5611", MS5611_BARO_DEVICE_PATH), _interface(interface), _prom(prom_buf.s), _measure_ticks(0), @@ -222,7 +223,7 @@ MS5611::~MS5611() stop_cycle(); if (_class_instance != -1) - unregister_class_devname(BARO_DEVICE_PATH, _class_instance); + unregister_class_devname(MS5611_BARO_DEVICE_PATH, _class_instance); /* free any existing reports */ if (_reports != nullptr) @@ -260,7 +261,54 @@ MS5611::init() /* register alternate interfaces if we have to */ _class_instance = register_class_devname(BARO_DEVICE_PATH); - ret = OK; + struct baro_report brp; + /* do a first measurement cycle to populate reports with valid data */ + _measure_phase = 0; + _reports->flush(); + + /* this do..while is goto without goto */ + do { + /* do temperature first */ + if (OK != measure()) { + ret = -EIO; + break; + } + + usleep(MS5611_CONVERSION_INTERVAL); + + if (OK != collect()) { + ret = -EIO; + break; + } + + /* now do a pressure measurement */ + if (OK != measure()) { + ret = -EIO; + break; + } + + usleep(MS5611_CONVERSION_INTERVAL); + + if (OK != collect()) { + ret = -EIO; + break; + } + + /* state machine will have generated a report, copy it out */ + _reports->get(&brp); + + ret = OK; + + if (_class_instance == CLASS_DEVICE_PRIMARY) { + + _baro_topic = orb_advertise(ORB_ID(sensor_baro), &brp); + + if (_baro_topic < 0) + debug("failed to create sensor_baro publication"); + } + + } while (0); + out: return ret; } @@ -668,17 +716,9 @@ MS5611::collect() report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a; /* publish it */ - if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { - - if (_baro_topic > 0) { - /* publish it */ - orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); - } else { - _baro_topic = orb_advertise(ORB_ID(sensor_baro), &report); - - if (_baro_topic < 0) - debug("failed to create sensor_baro publication"); - } + if (_baro_topic > 0 && !(_pub_blocked)) { + /* publish it */ + orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); } if (_reports->force(&report)) { @@ -821,7 +861,7 @@ start() goto fail; /* set the poll rate to default, starts automatic data collection */ - fd = open(BARO_DEVICE_PATH, O_RDONLY); + fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY); if (fd < 0) { warnx("can't open baro device"); goto fail; @@ -855,10 +895,10 @@ test() ssize_t sz; int ret; - int fd = open(BARO_DEVICE_PATH, O_RDONLY); + int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", BARO_DEVICE_PATH); + err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH); /* do a simple demand read */ sz = read(fd, &report, sizeof(report)); @@ -914,7 +954,7 @@ test() void reset() { - int fd = open(BARO_DEVICE_PATH, O_RDONLY); + int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY); if (fd < 0) err(1, "failed "); @@ -953,10 +993,10 @@ calibrate(unsigned altitude) float pressure; float p1; - int fd = open(BARO_DEVICE_PATH, O_RDONLY); + int fd = open(MS5611_BARO_DEVICE_PATH, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", BARO_DEVICE_PATH); + err(1, "%s open failed (try 'ms5611 start' if the driver is not running)", MS5611_BARO_DEVICE_PATH); /* start the sensor polling at max */ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX)) From 58d78e57b7b7de57a347ad94e70d2d19bb7230d0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 15:41:12 +0100 Subject: [PATCH 15/87] Build the sensors as part of the test binary --- makefiles/config_px4fmu-v1_test.mk | 3 +++ makefiles/config_px4fmu-v2_test.mk | 9 +++++++++ 2 files changed, 12 insertions(+) diff --git a/makefiles/config_px4fmu-v1_test.mk b/makefiles/config_px4fmu-v1_test.mk index 41e8b95ff5..300afa3d5b 100644 --- a/makefiles/config_px4fmu-v1_test.mk +++ b/makefiles/config_px4fmu-v1_test.mk @@ -29,6 +29,9 @@ MODULES += systemcmds/nshterm MODULES += modules/systemlib MODULES += modules/systemlib/mixer MODULES += modules/uORB +LIBRARIES += lib/mathlib/CMSIS +MODULES += lib/mathlib +MODULES += lib/mathlib/math/filter # # Transitional support - add commands from the NuttX export archive. diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index f54a4d8257..ea52213df0 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -18,6 +18,12 @@ MODULES += drivers/stm32/tone_alarm MODULES += drivers/led MODULES += drivers/boards/px4fmu-v2 MODULES += drivers/px4io +MODULES += drivers/rgbled +MODULES += drivers/mpu6000 +MODULES += drivers/lsm303d +MODULES += drivers/l3gd20 +MODULES += drivers/hmc5883 +MODULES += drivers/ms5611 MODULES += systemcmds/perf MODULES += systemcmds/reboot MODULES += systemcmds/tests @@ -30,6 +36,9 @@ MODULES += systemcmds/mtd MODULES += modules/systemlib MODULES += modules/systemlib/mixer MODULES += modules/uORB +LIBRARIES += lib/mathlib/CMSIS +MODULES += lib/mathlib +MODULES += lib/mathlib/math/filter # # Transitional support - add commands from the NuttX export archive. From bb8956c84e83c22d143a99d4ca37491574200438 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 16:04:12 +0100 Subject: [PATCH 16/87] Fixed return value --- src/drivers/device/cdev.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp index 65a9705f55..b157b3f181 100644 --- a/src/drivers/device/cdev.cpp +++ b/src/drivers/device/cdev.cpp @@ -261,6 +261,7 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg) break; case DEVIOCSPUBBLOCK: _pub_blocked = (arg != 0); + return OK; break; case DEVIOCGPUBBLOCK: return _pub_blocked; From ac326beaaae7b38d65ad6d7d13f00dfeaa6ae520 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 14 Jan 2014 16:04:26 +0100 Subject: [PATCH 17/87] Improved config tool to also do device IOCTLs --- src/systemcmds/config/config.c | 56 +++++++++++++++++++++++++++++----- 1 file changed, 49 insertions(+), 7 deletions(-) diff --git a/src/systemcmds/config/config.c b/src/systemcmds/config/config.c index 80689f20c8..476015f3e3 100644 --- a/src/systemcmds/config/config.c +++ b/src/systemcmds/config/config.c @@ -56,6 +56,7 @@ #include #include #include +#include #include "systemlib/systemlib.h" #include "systemlib/err.h" @@ -65,6 +66,7 @@ __EXPORT int config_main(int argc, char *argv[]); static void do_gyro(int argc, char *argv[]); static void do_accel(int argc, char *argv[]); static void do_mag(int argc, char *argv[]); +static void do_device(int argc, char *argv[]); int config_main(int argc, char *argv[]) @@ -72,20 +74,60 @@ config_main(int argc, char *argv[]) if (argc >= 2) { if (!strcmp(argv[1], "gyro")) { do_gyro(argc - 2, argv + 2); - } - - if (!strcmp(argv[1], "accel")) { + } else if (!strcmp(argv[1], "accel")) { do_accel(argc - 2, argv + 2); - } - - if (!strcmp(argv[1], "mag")) { + } else if (!strcmp(argv[1], "mag")) { do_mag(argc - 2, argv + 2); + } else { + do_device(argc - 1, argv + 1); } } errx(1, "expected a command, try 'gyro', 'accel', 'mag'"); } +static void +do_device(int argc, char *argv[]) +{ + if (argc < 2) { + errx(1, "no device path provided and command provided."); + } + + int fd; + int ret; + + fd = open(argv[0], 0); + + if (fd < 0) { + warn("%s", argv[0]); + errx(1, "FATAL: no device found"); + + } else { + + if (argc == 2 && !strcmp(argv[1], "block")) { + + /* disable the device publications */ + ret = ioctl(fd, DEVIOCSPUBBLOCK, 1); + + if (ret) + errx(ret,"uORB publications could not be blocked"); + + } else if (argc == 2 && !strcmp(argv[1], "unblock")) { + + /* enable the device publications */ + ret = ioctl(fd, DEVIOCSPUBBLOCK, 0); + + if (ret) + errx(ret,"uORB publications could not be unblocked"); + + } else { + errx("no valid command: %s", argv[1]); + } + } + + exit(0); +} + static void do_gyro(int argc, char *argv[]) { @@ -124,7 +166,7 @@ do_gyro(int argc, char *argv[]) if (ret) errx(ret,"range could not be set"); - } else if(argc == 1 && !strcmp(argv[0], "check")) { + } else if (argc == 1 && !strcmp(argv[0], "check")) { ret = ioctl(fd, GYROIOCSELFTEST, 0); if (ret) { From efc62a6c864766ce211906860d6325e4ca089241 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 2 Feb 2014 00:43:41 +0100 Subject: [PATCH 18/87] fw landing: improve slope altitude calc to avoid climbout after waypoint. Throttle cut is now defined via altitude --- .../fw_pos_control_l1_main.cpp | 25 ++++++++++--------- .../fw_pos_control_l1_params.c | 2 +- .../fw_pos_control_l1/landingslope.cpp | 22 ++++++++++++---- src/modules/fw_pos_control_l1/landingslope.h | 21 ++++++++++++---- 4 files changed, 47 insertions(+), 23 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 3ef1871a8b..45fdaa355e 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -236,7 +236,7 @@ private: float land_slope_length; float land_H1_virt; float land_flare_alt_relative; - float land_thrust_lim_horizontal_distance; + float land_thrust_lim_alt_relative; float land_heading_hold_horizontal_distance; } _parameters; /**< local copies of interesting parameters */ @@ -281,7 +281,7 @@ private: param_t land_slope_length; param_t land_H1_virt; param_t land_flare_alt_relative; - param_t land_thrust_lim_horizontal_distance; + param_t land_thrust_lim_alt_relative; param_t land_heading_hold_horizontal_distance; } _parameter_handles; /**< handles for interesting parameters */ @@ -434,7 +434,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.land_slope_length = param_find("FW_LND_SLLR"); _parameter_handles.land_H1_virt = param_find("FW_LND_HVIRT"); _parameter_handles.land_flare_alt_relative = param_find("FW_LND_FLALT"); - _parameter_handles.land_thrust_lim_horizontal_distance = param_find("FW_LND_TLDIST"); + _parameter_handles.land_thrust_lim_alt_relative = param_find("FW_LND_TLALT"); _parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST"); _parameter_handles.time_const = param_find("FW_T_TIME_CONST"); @@ -523,7 +523,7 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.land_slope_length, &(_parameters.land_slope_length)); param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt)); param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative)); - param_get(_parameter_handles.land_thrust_lim_horizontal_distance, &(_parameters.land_thrust_lim_horizontal_distance)); + param_get(_parameter_handles.land_thrust_lim_alt_relative, &(_parameters.land_thrust_lim_alt_relative)); param_get(_parameter_handles.land_heading_hold_horizontal_distance, &(_parameters.land_heading_hold_horizontal_distance)); _l1_control.set_l1_damping(_parameters.l1_damping); @@ -558,7 +558,7 @@ FixedwingPositionControl::parameters_update() } /* Update the landing slope */ - landingslope.update(math::radians(_parameters.land_slope_angle), _parameters.land_flare_alt_relative, _parameters.land_thrust_lim_horizontal_distance, _parameters.land_H1_virt); + landingslope.update(math::radians(_parameters.land_slope_angle), _parameters.land_flare_alt_relative, _parameters.land_thrust_lim_alt_relative, _parameters.land_H1_virt); /* Update and publish the navigation capabilities */ _nav_capabilities.landing_slope_angle_rad = landingslope.landing_slope_angle_rad(); @@ -836,6 +836,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_LAND) { + float bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); + /* Horizontal landing control */ /* switch to heading hold for the last meters, continue heading hold after */ float wp_distance = get_distance_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); @@ -846,7 +848,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (!land_noreturn_horizontal) {//set target_bearing in first occurrence if (pos_sp_triplet.previous.valid) { - target_bearing = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); + target_bearing = bearing_lastwp_currwp; } else { target_bearing = _att.yaw; } @@ -888,10 +890,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_approach = 1.3f * _parameters.airspeed_min; float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)) * _parameters.land_slope_length; - float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt);//getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt, landing_slope_angle_rad, horizontal_slope_displacement); - float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitude(wp_distance, _pos_sp_triplet.current.alt);//getLandingSlopeAbsoluteAltitude(wp_distance, _pos_sp_triplet.current.alt, landing_slope_angle_rad, horizontal_slope_displacement); - - + float L_altitude = landingslope.getLandingSlopeAbsoluteAltitude(L_wp_distance, _pos_sp_triplet.current.alt); + float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); + float landing_slope_alt_desired = landingslope.getLandingSlopeAbsoluteAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); if ( (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.flare_relative_alt()) || land_noreturn_vertical) { //checking for land_noreturn to avoid unwanted climb out @@ -903,7 +904,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi /* kill the throttle if param requests it */ throttle_max = _parameters.throttle_max; - if (wp_distance < landingslope.motor_lim_horizontal_distance() || land_motor_lim) { + if (_global_pos.alt < _pos_sp_triplet.current.alt + landingslope.motor_lim_relative_alt() || land_motor_lim) { throttle_max = math::min(throttle_max, _parameters.throttle_land_max); if (!land_motor_lim) { land_motor_lim = true; @@ -912,7 +913,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } - float flare_curve_alt = landingslope.getFlareCurveAltitude(wp_distance, _pos_sp_triplet.current.alt); + float flare_curve_alt = landingslope.getFlareCurveAltitudeSave(wp_distance, bearing_lastwp_currwp, bearing_airplane_currwp, _pos_sp_triplet.current.alt); /* avoid climbout */ if (flare_curve_alt_last < flare_curve_alt && land_noreturn_vertical || land_stayonground) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 7954d75c20..ee8721ff92 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -172,5 +172,5 @@ PARAM_DEFINE_FLOAT(FW_LND_ANG, 10.0f); PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f); -PARAM_DEFINE_FLOAT(FW_LND_TLDIST, 30.0f); +PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f); PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); diff --git a/src/modules/fw_pos_control_l1/landingslope.cpp b/src/modules/fw_pos_control_l1/landingslope.cpp index b139a63978..e5f7023ae1 100644 --- a/src/modules/fw_pos_control_l1/landingslope.cpp +++ b/src/modules/fw_pos_control_l1/landingslope.cpp @@ -48,13 +48,13 @@ void Landingslope::update(float landing_slope_angle_rad, float flare_relative_alt, - float motor_lim_horizontal_distance, + float motor_lim_relative_alt, float H1_virt) { _landing_slope_angle_rad = landing_slope_angle_rad; _flare_relative_alt = flare_relative_alt; - _motor_lim_horizontal_distance = motor_lim_horizontal_distance; + _motor_lim_relative_alt = motor_lim_relative_alt; _H1_virt = H1_virt; calculateSlopeValues(); @@ -74,9 +74,21 @@ float Landingslope::getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_ return Landingslope::getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude, _horizontal_slope_displacement, _landing_slope_angle_rad); } -float Landingslope::getFlareCurveAltitude(float wp_landing_distance, float wp_landing_altitude) +float Landingslope::getLandingSlopeAbsoluteAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude) { - return wp_landing_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt; - + /* If airplane is in front of waypoint return slope altitude, else return waypoint altitude */ + if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f)) + return getLandingSlopeAbsoluteAltitude(wp_distance, wp_altitude); + else + return wp_altitude; +} + +float Landingslope::getFlareCurveAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude) +{ + /* If airplane is in front of waypoint return flare curve altitude, else return waypoint altitude */ + if (fabsf(bearing_airplane_currwp - bearing_lastwp_currwp) < math::radians(90.0f)) + return wp_landing_altitude + _H0 * expf(-math::max(0.0f, _flare_length - wp_landing_distance)/_flare_constant) - _H1_virt; + else + return wp_landing_altitude; } diff --git a/src/modules/fw_pos_control_l1/landingslope.h b/src/modules/fw_pos_control_l1/landingslope.h index 1a149fc7cd..76d65a55f2 100644 --- a/src/modules/fw_pos_control_l1/landingslope.h +++ b/src/modules/fw_pos_control_l1/landingslope.h @@ -49,7 +49,7 @@ private: /* see Documentation/fw_landing.png for a plot of the landing slope */ float _landing_slope_angle_rad; /**< phi in the plot */ float _flare_relative_alt; /**< h_flare,rel in the plot */ - float _motor_lim_horizontal_distance; + float _motor_lim_relative_alt; float _H1_virt; /**< H1 in the plot */ float _H0; /**< h_flare,rel + H1 in the plot */ float _d1; /**< d1 in the plot */ @@ -63,7 +63,18 @@ public: Landingslope() {} ~Landingslope() {} - float getLandingSlopeAbsoluteAltitude(float wp_landing_distance, float wp_landing_altitude); + /** + * + * @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance + */ + float getLandingSlopeAbsoluteAltitude(float wp_distance, float wp_altitude); + + /** + * + * @return Absolute altitude of point on landing slope at distance to landing waypoint=wp_landing_distance + * Performs check if aircraft is in front of waypoint to avoid climbout + */ + float getLandingSlopeAbsoluteAltitudeSave(float wp_landing_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_landing_altitude); /** * @@ -85,17 +96,17 @@ public: } - float getFlareCurveAltitude(float wp_distance, float wp_altitude); + float getFlareCurveAltitudeSave(float wp_distance, float bearing_lastwp_currwp, float bearing_airplane_currwp, float wp_altitude); void update(float landing_slope_angle_rad, float flare_relative_alt, - float motor_lim_horizontal_distance, + float motor_lim_relative_alt, float H1_virt); inline float landing_slope_angle_rad() {return _landing_slope_angle_rad;} inline float flare_relative_alt() {return _flare_relative_alt;} - inline float motor_lim_horizontal_distance() {return _motor_lim_horizontal_distance;} + inline float motor_lim_relative_alt() {return _motor_lim_relative_alt;} inline float H1_virt() {return _H1_virt;} inline float H0() {return _H0;} inline float d1() {return _d1;} From 9defc6cb235e13ef912a70466acf1d14314f1e3d Mon Sep 17 00:00:00 2001 From: marco Date: Sun, 2 Feb 2014 14:26:17 +0100 Subject: [PATCH 19/87] mkblctrl fmuv2 support added --- makefiles/config_px4fmu-v2_default.mk | 2 + src/drivers/mkblctrl/mkblctrl.cpp | 152 +++++++++++++++++++++++++- 2 files changed, 148 insertions(+), 6 deletions(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 880e2738ac..dc9208339b 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -38,6 +38,8 @@ MODULES += drivers/ets_airspeed MODULES += drivers/meas_airspeed MODULES += drivers/frsky_telemetry MODULES += modules/sensors +MODULES += drivers/mkblctrl + # Needs to be burned to the ground and re-written; for now, # just don't build it. diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index 30d6069b32..dbba91786b 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012,2013 PX4 Development Team. All rights reserved. + * Copyright (C) 2012-2014 PX4 Development Team. All rights reserved. * Author: Marco Bauer * * Redistribution and use in source and binary forms, with or without @@ -93,6 +93,9 @@ #define MOTOR_SPINUP_COUNTER 30 #define ESC_UORB_PUBLISH_DELAY 500000 + + + class MK : public device::I2C { public: @@ -181,6 +184,7 @@ private: static const unsigned _ngpio; void gpio_reset(void); + void sensor_reset(int ms); void gpio_set_function(uint32_t gpios, int function); void gpio_write(uint32_t gpios, int function); uint32_t gpio_read(void); @@ -196,6 +200,7 @@ private: }; const MK::GPIOConfig MK::_gpio_tab[] = { +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, @@ -204,6 +209,22 @@ const MK::GPIOConfig MK::_gpio_tab[] = { {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1}, {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, +#endif +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) + {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, + {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, + {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, + {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, + {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, + {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, + + {0, GPIO_VDD_5V_PERIPH_EN, 0}, + {0, GPIO_VDD_3V3_SENSORS_EN, 0}, + {GPIO_VDD_BRICK_VALID, 0, 0}, + {GPIO_VDD_SERVO_VALID, 0, 0}, + {GPIO_VDD_5V_HIPOWER_OC, 0, 0}, + {GPIO_VDD_5V_PERIPH_OC, 0, 0}, +#endif }; const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]); @@ -623,9 +644,11 @@ MK::task_main() if(!_overrideSecurityChecks) { /* don't go under BLCTRL_MIN_VALUE */ + if (outputs.output[i] < BLCTRL_MIN_VALUE) { outputs.output[i] = BLCTRL_MIN_VALUE; } + } /* output to BLCtrl's */ @@ -1075,6 +1098,10 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) ret = OK; break; + case PWM_SERVO_GET_UPDATE_RATE: + *(uint32_t *)arg = 400; + break; + case PWM_SERVO_SET_SELECT_UPDATE_RATE: ret = OK; break; @@ -1198,23 +1225,115 @@ MK::write(file *filp, const char *buffer, size_t len) return count * 2; } +void +MK::sensor_reset(int ms) +{ +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) + + if (ms < 1) { + ms = 1; + } + + /* disable SPI bus */ + stm32_configgpio(GPIO_SPI_CS_GYRO_OFF); + stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF); + stm32_configgpio(GPIO_SPI_CS_BARO_OFF); + stm32_configgpio(GPIO_SPI_CS_MPU_OFF); + + stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0); + stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0); + stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0); + stm32_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0); + + stm32_configgpio(GPIO_SPI1_SCK_OFF); + stm32_configgpio(GPIO_SPI1_MISO_OFF); + stm32_configgpio(GPIO_SPI1_MOSI_OFF); + + stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0); + stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0); + stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0); + + stm32_configgpio(GPIO_GYRO_DRDY_OFF); + stm32_configgpio(GPIO_MAG_DRDY_OFF); + stm32_configgpio(GPIO_ACCEL_DRDY_OFF); + stm32_configgpio(GPIO_EXTI_MPU_DRDY_OFF); + + stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0); + stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0); + stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0); + stm32_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0); + + /* set the sensor rail off */ + stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN); + stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0); + + /* wait for the sensor rail to reach GND */ + usleep(ms * 1000); + warnx("reset done, %d ms", ms); + + /* re-enable power */ + + /* switch the sensor rail back on */ + stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1); + + /* wait a bit before starting SPI, different times didn't influence results */ + usleep(100); + + /* reconfigure the SPI pins */ +#ifdef CONFIG_STM32_SPI1 + stm32_configgpio(GPIO_SPI_CS_GYRO); + stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG); + stm32_configgpio(GPIO_SPI_CS_BARO); + stm32_configgpio(GPIO_SPI_CS_MPU); + + /* De-activate all peripherals, + * required for some peripheral + * state machines + */ + stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); + stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1); + stm32_gpiowrite(GPIO_SPI_CS_BARO, 1); + stm32_gpiowrite(GPIO_SPI_CS_MPU, 1); + + // // XXX bring up the EXTI pins again + // stm32_configgpio(GPIO_GYRO_DRDY); + // stm32_configgpio(GPIO_MAG_DRDY); + // stm32_configgpio(GPIO_ACCEL_DRDY); + // stm32_configgpio(GPIO_EXTI_MPU_DRDY); + +#endif +#endif +} + + void MK::gpio_reset(void) { /* - * Setup default GPIO config - all pins as GPIOs, GPIO driver chip - * to input mode. + * Setup default GPIO config - all pins as GPIOs, input if + * possible otherwise output if possible. */ - for (unsigned i = 0; i < _ngpio; i++) - stm32_configgpio(_gpio_tab[i].input); + for (unsigned i = 0; i < _ngpio; i++) { + if (_gpio_tab[i].input != 0) { + stm32_configgpio(_gpio_tab[i].input); + } else if (_gpio_tab[i].output != 0) { + stm32_configgpio(_gpio_tab[i].output); + } + } + +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) + /* if we have a GPIO direction control, set it to zero (input) */ stm32_gpiowrite(GPIO_GPIO_DIR, 0); stm32_configgpio(GPIO_GPIO_DIR); +#endif } void MK::gpio_set_function(uint32_t gpios, int function) { +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) + /* * GPIOs 0 and 1 must have the same direction as they are buffered * by a shared 2-port driver. Any attempt to set either sets both. @@ -1227,6 +1346,8 @@ MK::gpio_set_function(uint32_t gpios, int function) stm32_gpiowrite(GPIO_GPIO_DIR, 1); } +#endif + /* configure selected GPIOs as required */ for (unsigned i = 0; i < _ngpio; i++) { if (gpios & (1 << i)) { @@ -1248,9 +1369,13 @@ MK::gpio_set_function(uint32_t gpios, int function) } } +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) + /* flip buffer to input mode if required */ if ((GPIO_SET_INPUT == function) && (gpios & 3)) stm32_gpiowrite(GPIO_GPIO_DIR, 0); + +#endif } void @@ -1418,6 +1543,20 @@ mk_start(unsigned bus, unsigned motors, char *device_path) return ret; } +void +sensor_reset(int ms) +{ + int fd; + + fd = open(PX4FMU_DEVICE_PATH, O_RDWR); + + if (fd < 0) + errx(1, "open fail"); + + if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0) + err(1, "servo arm failed"); + +} int mk_check_for_i2c_esc_bus(char *device_path, int motors) @@ -1426,6 +1565,7 @@ mk_check_for_i2c_esc_bus(char *device_path, int motors) if (g_mk == nullptr) { +#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) g_mk = new MK(3, device_path); if (g_mk == nullptr) { @@ -1441,7 +1581,7 @@ mk_check_for_i2c_esc_bus(char *device_path, int motors) } } - +#endif g_mk = new MK(1, device_path); From 0089db7ef3961c36d6513877b7681ab548d20ccf Mon Sep 17 00:00:00 2001 From: marco Date: Sun, 2 Feb 2014 16:28:56 +0100 Subject: [PATCH 20/87] code cleanup --- src/drivers/mkblctrl/mkblctrl.cpp | 425 +++--------------------------- 1 file changed, 30 insertions(+), 395 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index dbba91786b..c3c4bf8c1d 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -65,7 +65,7 @@ #include #include -#include +//#include #include #include @@ -123,8 +123,7 @@ public: virtual int init(unsigned motors); virtual ssize_t write(file *filp, const char *buffer, size_t len); - int set_mode(Mode mode); - int set_pwm_rate(unsigned rate); + int set_update_rate(unsigned rate); int set_motor_count(unsigned count); int set_motor_test(bool motortest); int set_overrideSecurityChecks(bool overrideSecurityChecks); @@ -136,7 +135,6 @@ private: static const unsigned _max_actuators = MAX_MOTORS; static const bool showDebug = false; - Mode _mode; int _update_rate; int _current_update_rate; int _task; @@ -183,51 +181,15 @@ private: static const GPIOConfig _gpio_tab[]; static const unsigned _ngpio; - void gpio_reset(void); - void sensor_reset(int ms); - void gpio_set_function(uint32_t gpios, int function); - void gpio_write(uint32_t gpios, int function); - uint32_t gpio_read(void); - int gpio_ioctl(file *filp, int cmd, unsigned long arg); int mk_servo_arm(bool status); - int mk_servo_set(unsigned int chan, short val); int mk_servo_set_value(unsigned int chan, short val); int mk_servo_test(unsigned int chan); short scaling(float val, float inMin, float inMax, float outMin, float outMax); - - }; -const MK::GPIOConfig MK::_gpio_tab[] = { -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, - {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, - {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, GPIO_USART2_CTS_1}, - {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, GPIO_USART2_RTS_1}, - {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, GPIO_USART2_TX_1}, - {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, GPIO_USART2_RX_1}, - {GPIO_GPIO6_INPUT, GPIO_GPIO6_OUTPUT, GPIO_CAN2_TX_2}, - {GPIO_GPIO7_INPUT, GPIO_GPIO7_OUTPUT, GPIO_CAN2_RX_2}, -#endif -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) - {GPIO_GPIO0_INPUT, GPIO_GPIO0_OUTPUT, 0}, - {GPIO_GPIO1_INPUT, GPIO_GPIO1_OUTPUT, 0}, - {GPIO_GPIO2_INPUT, GPIO_GPIO2_OUTPUT, 0}, - {GPIO_GPIO3_INPUT, GPIO_GPIO3_OUTPUT, 0}, - {GPIO_GPIO4_INPUT, GPIO_GPIO4_OUTPUT, 0}, - {GPIO_GPIO5_INPUT, GPIO_GPIO5_OUTPUT, 0}, - {0, GPIO_VDD_5V_PERIPH_EN, 0}, - {0, GPIO_VDD_3V3_SENSORS_EN, 0}, - {GPIO_VDD_BRICK_VALID, 0, 0}, - {GPIO_VDD_SERVO_VALID, 0, 0}, - {GPIO_VDD_5V_HIPOWER_OC, 0, 0}, - {GPIO_VDD_5V_PERIPH_OC, 0, 0}, -#endif -}; -const unsigned MK::_ngpio = sizeof(MK::_gpio_tab) / sizeof(MK::_gpio_tab[0]); const int blctrlAddr_quad_plus[] = { 2, 2, -2, -2, 0, 0, 0, 0 }; // Addresstranslator for Quad + configuration const int blctrlAddr_hexa_plus[] = { 0, 2, 2, -2, 1, -3, 0, 0 }; // Addresstranslator for Hexa + configuration @@ -268,8 +230,7 @@ MK *g_mk; MK::MK(int bus, const char *_device_path) : I2C("mkblctrl", "/dev/mkblctrl", bus, 0, I2C_BUS_SPEED), - _mode(MODE_NONE), - _update_rate(50), + _update_rate(400), _task(-1), _t_actuators(-1), _t_actuator_armed(-1), @@ -348,9 +309,6 @@ MK::init(unsigned motors) } - /* reset GPIOs */ - gpio_reset(); - /* start the IO interface task */ _task = task_spawn_cmd("mkblctrl", SCHED_DEFAULT, @@ -375,43 +333,7 @@ MK::task_main_trampoline(int argc, char *argv[]) } int -MK::set_mode(Mode mode) -{ - /* - * Configure for PWM output. - * - * Note that regardless of the configured mode, the task is always - * listening and mixing; the mode just selects which of the channels - * are presented on the output pins. - */ - switch (mode) { - case MODE_2PWM: - up_pwm_servo_deinit(); - _update_rate = UPDATE_RATE; /* default output rate */ - break; - - case MODE_4PWM: - up_pwm_servo_deinit(); - _update_rate = UPDATE_RATE; /* default output rate */ - break; - - case MODE_NONE: - debug("MODE_NONE"); - /* disable servo outputs and set a very low update rate */ - up_pwm_servo_deinit(); - _update_rate = UPDATE_RATE; - break; - - default: - return -EINVAL; - } - - _mode = mode; - return OK; -} - -int -MK::set_pwm_rate(unsigned rate) +MK::set_update_rate(unsigned rate) { if ((rate > 500) || (rate < 10)) return -EINVAL; @@ -1042,28 +964,6 @@ MK::ioctl(file *filp, int cmd, unsigned long arg) { int ret; - // XXX disabled, confusing users - - /* try it as a GPIO ioctl first */ - ret = gpio_ioctl(filp, cmd, arg); - - if (ret != -ENOTTY) - return ret; - - /* if we are in valid PWM mode, try it as a PWM ioctl as well */ - /* - switch (_mode) { - case MODE_2PWM: - case MODE_4PWM: - case MODE_6PWM: - ret = pwm_ioctl(filp, cmd, arg); - break; - - default: - debug("not in a PWM mode"); - break; - } - */ ret = pwm_ioctl(filp, cmd, arg); /* if nobody wants it, let CDev have it */ @@ -1099,7 +999,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; case PWM_SERVO_GET_UPDATE_RATE: - *(uint32_t *)arg = 400; + *(uint32_t *)arg = _update_rate; break; case PWM_SERVO_SET_SELECT_UPDATE_RATE: @@ -1225,237 +1125,10 @@ MK::write(file *filp, const char *buffer, size_t len) return count * 2; } -void -MK::sensor_reset(int ms) -{ -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V2) - - if (ms < 1) { - ms = 1; - } - - /* disable SPI bus */ - stm32_configgpio(GPIO_SPI_CS_GYRO_OFF); - stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG_OFF); - stm32_configgpio(GPIO_SPI_CS_BARO_OFF); - stm32_configgpio(GPIO_SPI_CS_MPU_OFF); - - stm32_gpiowrite(GPIO_SPI_CS_GYRO_OFF, 0); - stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG_OFF, 0); - stm32_gpiowrite(GPIO_SPI_CS_BARO_OFF, 0); - stm32_gpiowrite(GPIO_SPI_CS_MPU_OFF, 0); - - stm32_configgpio(GPIO_SPI1_SCK_OFF); - stm32_configgpio(GPIO_SPI1_MISO_OFF); - stm32_configgpio(GPIO_SPI1_MOSI_OFF); - - stm32_gpiowrite(GPIO_SPI1_SCK_OFF, 0); - stm32_gpiowrite(GPIO_SPI1_MISO_OFF, 0); - stm32_gpiowrite(GPIO_SPI1_MOSI_OFF, 0); - - stm32_configgpio(GPIO_GYRO_DRDY_OFF); - stm32_configgpio(GPIO_MAG_DRDY_OFF); - stm32_configgpio(GPIO_ACCEL_DRDY_OFF); - stm32_configgpio(GPIO_EXTI_MPU_DRDY_OFF); - - stm32_gpiowrite(GPIO_GYRO_DRDY_OFF, 0); - stm32_gpiowrite(GPIO_MAG_DRDY_OFF, 0); - stm32_gpiowrite(GPIO_ACCEL_DRDY_OFF, 0); - stm32_gpiowrite(GPIO_EXTI_MPU_DRDY_OFF, 0); - - /* set the sensor rail off */ - stm32_configgpio(GPIO_VDD_3V3_SENSORS_EN); - stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 0); - - /* wait for the sensor rail to reach GND */ - usleep(ms * 1000); - warnx("reset done, %d ms", ms); - - /* re-enable power */ - - /* switch the sensor rail back on */ - stm32_gpiowrite(GPIO_VDD_3V3_SENSORS_EN, 1); - - /* wait a bit before starting SPI, different times didn't influence results */ - usleep(100); - - /* reconfigure the SPI pins */ -#ifdef CONFIG_STM32_SPI1 - stm32_configgpio(GPIO_SPI_CS_GYRO); - stm32_configgpio(GPIO_SPI_CS_ACCEL_MAG); - stm32_configgpio(GPIO_SPI_CS_BARO); - stm32_configgpio(GPIO_SPI_CS_MPU); - - /* De-activate all peripherals, - * required for some peripheral - * state machines - */ - stm32_gpiowrite(GPIO_SPI_CS_GYRO, 1); - stm32_gpiowrite(GPIO_SPI_CS_ACCEL_MAG, 1); - stm32_gpiowrite(GPIO_SPI_CS_BARO, 1); - stm32_gpiowrite(GPIO_SPI_CS_MPU, 1); - - // // XXX bring up the EXTI pins again - // stm32_configgpio(GPIO_GYRO_DRDY); - // stm32_configgpio(GPIO_MAG_DRDY); - // stm32_configgpio(GPIO_ACCEL_DRDY); - // stm32_configgpio(GPIO_EXTI_MPU_DRDY); - -#endif -#endif -} - - -void -MK::gpio_reset(void) -{ - /* - * Setup default GPIO config - all pins as GPIOs, input if - * possible otherwise output if possible. - */ - for (unsigned i = 0; i < _ngpio; i++) { - if (_gpio_tab[i].input != 0) { - stm32_configgpio(_gpio_tab[i].input); - - } else if (_gpio_tab[i].output != 0) { - stm32_configgpio(_gpio_tab[i].output); - } - } - -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - /* if we have a GPIO direction control, set it to zero (input) */ - stm32_gpiowrite(GPIO_GPIO_DIR, 0); - stm32_configgpio(GPIO_GPIO_DIR); -#endif -} - -void -MK::gpio_set_function(uint32_t gpios, int function) -{ -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - - /* - * GPIOs 0 and 1 must have the same direction as they are buffered - * by a shared 2-port driver. Any attempt to set either sets both. - */ - if (gpios & 3) { - gpios |= 3; - - /* flip the buffer to output mode if required */ - if (GPIO_SET_OUTPUT == function) - stm32_gpiowrite(GPIO_GPIO_DIR, 1); - } - -#endif - - /* configure selected GPIOs as required */ - for (unsigned i = 0; i < _ngpio; i++) { - if (gpios & (1 << i)) { - switch (function) { - case GPIO_SET_INPUT: - stm32_configgpio(_gpio_tab[i].input); - break; - - case GPIO_SET_OUTPUT: - stm32_configgpio(_gpio_tab[i].output); - break; - - case GPIO_SET_ALT_1: - if (_gpio_tab[i].alt != 0) - stm32_configgpio(_gpio_tab[i].alt); - - break; - } - } - } - -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - - /* flip buffer to input mode if required */ - if ((GPIO_SET_INPUT == function) && (gpios & 3)) - stm32_gpiowrite(GPIO_GPIO_DIR, 0); - -#endif -} - -void -MK::gpio_write(uint32_t gpios, int function) -{ - int value = (function == GPIO_SET) ? 1 : 0; - - for (unsigned i = 0; i < _ngpio; i++) - if (gpios & (1 << i)) - stm32_gpiowrite(_gpio_tab[i].output, value); -} - -uint32_t -MK::gpio_read(void) -{ - uint32_t bits = 0; - - for (unsigned i = 0; i < _ngpio; i++) - if (stm32_gpioread(_gpio_tab[i].input)) - bits |= (1 << i); - - return bits; -} - -int -MK::gpio_ioctl(struct file *filp, int cmd, unsigned long arg) -{ - int ret = OK; - - lock(); - - switch (cmd) { - - case GPIO_RESET: - gpio_reset(); - break; - - case GPIO_SET_OUTPUT: - case GPIO_SET_INPUT: - case GPIO_SET_ALT_1: - gpio_set_function(arg, cmd); - break; - - case GPIO_SET_ALT_2: - case GPIO_SET_ALT_3: - case GPIO_SET_ALT_4: - ret = -EINVAL; - break; - - case GPIO_SET: - case GPIO_CLEAR: - gpio_write(arg, cmd); - break; - - case GPIO_GET: - *(uint32_t *)arg = gpio_read(); - break; - - default: - ret = -ENOTTY; - } - - unlock(); - - return ret; -} namespace { -enum PortMode { - PORT_MODE_UNSET = 0, - PORT_FULL_GPIO, - PORT_FULL_SERIAL, - PORT_FULL_PWM, - PORT_GPIO_AND_SERIAL, - PORT_PWM_AND_SERIAL, - PORT_PWM_AND_GPIO, -}; - enum MappingMode { MAPPING_MK = 0, MAPPING_PX4, @@ -1466,20 +1139,11 @@ enum FrameType { FRAME_X, }; -PortMode g_port_mode; int -mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks) +mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int frametype, bool overrideSecurityChecks) { - uint32_t gpio_bits; int shouldStop = 0; - MK::Mode servo_mode; - - /* reset to all-inputs */ - g_mk->ioctl(0, GPIO_RESET, 0); - - gpio_bits = 0; - servo_mode = MK::MODE_NONE; /* native PX4 addressing) */ g_mk->set_px4mode(px4mode); @@ -1493,7 +1157,6 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, /* ovveride security checks if enabled */ g_mk->set_overrideSecurityChecks(overrideSecurityChecks); - /* count used motors */ do { if (g_mk->mk_check_for_blctrl(8, false, false) != 0) { @@ -1508,12 +1171,7 @@ mk_new_mode(PortMode new_mode, int update_rate, int motorcount, bool motortest, g_mk->set_motor_count(g_mk->mk_check_for_blctrl(8, true, false)); - /* (re)set the PWM output mode */ - g_mk->set_mode(servo_mode); - - - if ((servo_mode != MK::MODE_NONE) && (update_rate != 0)) - g_mk->set_pwm_rate(update_rate); + g_mk->set_update_rate(update_rate); return OK; } @@ -1543,60 +1201,38 @@ mk_start(unsigned bus, unsigned motors, char *device_path) return ret; } -void -sensor_reset(int ms) -{ - int fd; - - fd = open(PX4FMU_DEVICE_PATH, O_RDWR); - - if (fd < 0) - errx(1, "open fail"); - - if (ioctl(fd, GPIO_SENSOR_RAIL_RESET, ms) < 0) - err(1, "servo arm failed"); - -} int mk_check_for_i2c_esc_bus(char *device_path, int motors) { int ret; + g_mk = new MK(1, device_path); + if (g_mk == nullptr) { - -#if defined(CONFIG_ARCH_BOARD_PX4FMU_V1) - g_mk = new MK(3, device_path); - - if (g_mk == nullptr) { - return -1; - - } else { - ret = g_mk->mk_check_for_blctrl(8, false, true); - delete g_mk; - g_mk = nullptr; - - if (ret > 0) { - return 3; - } - + return -1; + } else if (OK != g_mk) { + delete g_mk; + g_mk = nullptr; + } else { + ret = g_mk->mk_check_for_blctrl(8, false, true); + delete g_mk; + g_mk = nullptr; + if (ret > 0) { + return 3; } -#endif + } - g_mk = new MK(1, device_path); - - if (g_mk == nullptr) { - return -1; - - } else { - ret = g_mk->mk_check_for_blctrl(8, false, true); - delete g_mk; - g_mk = nullptr; - - if (ret > 0) { - return 1; - } + g_mk = new MK(1, device_path); + if (g_mk == nullptr) { + return -1; + } else { + ret = g_mk->mk_check_for_blctrl(8, false, true); + delete g_mk; + g_mk = nullptr; + if (ret > 0) { + return 1; } } @@ -1612,7 +1248,6 @@ extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); int mkblctrl_main(int argc, char *argv[]) { - PortMode port_mode = PORT_FULL_PWM; int pwm_update_rate_in_hz = UPDATE_RATE; int motorcount = 8; int bus = -1; @@ -1729,7 +1364,7 @@ mkblctrl_main(int argc, char *argv[]) /* parameter set ? */ if (newMode) { /* switch parameter */ - return mk_new_mode(port_mode, pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks); + return mk_new_mode(pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks); } exit(0); From 816229652f1eecf8322603eb918f787bdd77d7e2 Mon Sep 17 00:00:00 2001 From: marco Date: Sun, 2 Feb 2014 20:36:11 +0100 Subject: [PATCH 21/87] i2c1 bug and bus scan fixed --- src/drivers/mkblctrl/mkblctrl.cpp | 62 +++++++++++++++---------------- 1 file changed, 29 insertions(+), 33 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index c3c4bf8c1d..f692a0dd0d 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -65,7 +65,6 @@ #include #include -//#include #include #include @@ -99,13 +98,6 @@ class MK : public device::I2C { public: - enum Mode { - MODE_NONE, - MODE_2PWM, - MODE_4PWM, - MODE_6PWM, - }; - enum MappingMode { MAPPING_MK = 0, MAPPING_PX4, @@ -1207,11 +1199,11 @@ mk_check_for_i2c_esc_bus(char *device_path, int motors) { int ret; - g_mk = new MK(1, device_path); + // try bus 3 first + warnx("scanning i2c3..."); + g_mk = new MK(3, device_path); - if (g_mk == nullptr) { - return -1; - } else if (OK != g_mk) { + if (g_mk != nullptr && OK != g_mk->init(motors)) { delete g_mk; g_mk = nullptr; } else { @@ -1223,10 +1215,13 @@ mk_check_for_i2c_esc_bus(char *device_path, int motors) } } + // fallback to bus 1 + warnx("scanning i2c1..."); g_mk = new MK(1, device_path); - if (g_mk == nullptr) { - return -1; + if (g_mk != nullptr && OK != g_mk->init(motors)) { + delete g_mk; + g_mk = nullptr; } else { ret = g_mk->mk_check_for_blctrl(8, false, true); delete g_mk; @@ -1240,7 +1235,6 @@ mk_check_for_i2c_esc_bus(char *device_path, int motors) } - } // namespace extern "C" __EXPORT int mkblctrl_main(int argc, char *argv[]); @@ -1348,31 +1342,33 @@ mkblctrl_main(int argc, char *argv[]) if (!motortest) { - if (g_mk == nullptr) { - if (bus == -1) { - bus = mk_check_for_i2c_esc_bus(devicepath, motorcount); - } + if (g_mk == nullptr) { + if (bus == -1) { + bus = mk_check_for_i2c_esc_bus(devicepath, motorcount); - if (bus != -1) { + + } + + if (bus != -1) { if (mk_start(bus, motorcount, devicepath) != OK) { errx(1, "failed to start the MK-BLCtrl driver"); } - } else { - errx(1, "failed to start the MK-BLCtrl driver (cannot find i2c esc's)"); - } + } else { + errx(1, "failed to start the MK-BLCtrl driver (cannot find i2c esc's)"); + } - /* parameter set ? */ - if (newMode) { - /* switch parameter */ - return mk_new_mode(pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks); - } + /* parameter set ? */ + if (newMode) { + /* switch parameter */ + return mk_new_mode(pwm_update_rate_in_hz, motorcount, motortest, px4mode, frametype, overrideSecurityChecks); + } - exit(0); - } else { - errx(1, "MK-BLCtrl driver already running"); - } + exit(0); + } else { + errx(1, "MK-BLCtrl driver already running"); + } - } else { + } else { if (g_mk == nullptr) { errx(1, "MK-BLCtrl driver not running. You have to start it first."); From 1ef7320e0c9fe00fdc13b1078d6350240a337179 Mon Sep 17 00:00:00 2001 From: marco Date: Tue, 4 Feb 2014 16:50:22 +0100 Subject: [PATCH 22/87] startup rewrite --- src/drivers/mkblctrl/mkblctrl.cpp | 108 ++++++++---------------------- 1 file changed, 27 insertions(+), 81 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index f692a0dd0d..d1c817cf31 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -1169,69 +1169,39 @@ mk_new_mode(int update_rate, int motorcount, bool motortest, int px4mode, int fr } int -mk_start(unsigned bus, unsigned motors, char *device_path) -{ - int ret = OK; - - if (g_mk == nullptr) { - - g_mk = new MK(bus, device_path); - - if (g_mk == nullptr) { - ret = -ENOMEM; - - } else { - ret = g_mk->init(motors); - - if (ret != OK) { - delete g_mk; - g_mk = nullptr; - } - } - } - - return ret; -} - - -int -mk_check_for_i2c_esc_bus(char *device_path, int motors) +mk_start(unsigned motors, char *device_path) { int ret; - // try bus 3 first - warnx("scanning i2c3..."); - g_mk = new MK(3, device_path); + // try i2c3 first + g_mk = new MK(3, device_path); - if (g_mk != nullptr && OK != g_mk->init(motors)) { - delete g_mk; - g_mk = nullptr; - } else { - ret = g_mk->mk_check_for_blctrl(8, false, true); - delete g_mk; - g_mk = nullptr; - if (ret > 0) { - return 3; - } - } + if (g_mk && OK == g_mk->init(motors)) { + fprintf(stderr, "[mkblctrl] scanning i2c3...\n"); + ret = g_mk->mk_check_for_blctrl(8, false, true); + if (ret > 0) { + return OK; + } + } + + delete g_mk; + g_mk = nullptr; // fallback to bus 1 - warnx("scanning i2c1..."); g_mk = new MK(1, device_path); - if (g_mk != nullptr && OK != g_mk->init(motors)) { - delete g_mk; - g_mk = nullptr; - } else { - ret = g_mk->mk_check_for_blctrl(8, false, true); - delete g_mk; - g_mk = nullptr; - if (ret > 0) { - return 1; - } - } + if (g_mk && OK == g_mk->init(motors)) { + fprintf(stderr, "[mkblctrl] scanning i2c1...\n"); + ret = g_mk->mk_check_for_blctrl(8, false, true); + if (ret > 0) { + return OK; + } + } - return -1; + delete g_mk; + g_mk = nullptr; + + return -ENOMEM; } @@ -1244,7 +1214,6 @@ mkblctrl_main(int argc, char *argv[]) { int pwm_update_rate_in_hz = UPDATE_RATE; int motorcount = 8; - int bus = -1; int px4mode = MAPPING_PX4; int frametype = FRAME_PLUS; // + plus is default bool motortest = false; @@ -1258,18 +1227,6 @@ mkblctrl_main(int argc, char *argv[]) */ for (int i = 1; i < argc; i++) { - /* look for the optional i2c bus parameter */ - if (strcmp(argv[i], "-b") == 0 || strcmp(argv[i], "--bus") == 0) { - if (argc > i + 1) { - bus = atoi(argv[i + 1]); - newMode = true; - - } else { - errx(1, "missing argument for i2c bus (-b)"); - return 1; - } - } - /* look for the optional frame parameter */ if (strcmp(argv[i], "-mkmode") == 0 || strcmp(argv[i], "--mkmode") == 0) { if (argc > i + 1) { @@ -1329,7 +1286,6 @@ mkblctrl_main(int argc, char *argv[]) fprintf(stderr, "mkblctrl: help:\n"); fprintf(stderr, " [-mkmode {+/x}] [-b i2c_bus_number] [-d devicename] [--override-security-checks] [-h / --help]\n\n"); fprintf(stderr, "\t -mkmode {+/x} \t\t Type of frame, if Mikrokopter motor order is used.\n"); - fprintf(stderr, "\t -b {i2c_bus_number} \t\t Set the i2c bus where the ESCs are connected to (default autoscan).\n"); fprintf(stderr, "\t -d {devicepath & name}\t\t Create alternate pwm device.\n"); fprintf(stderr, "\t --override-security-checks \t\t Disable all security checks (arming and number of ESCs). Used to test single Motors etc. (DANGER !!!)\n"); fprintf(stderr, "\n"); @@ -1343,19 +1299,9 @@ mkblctrl_main(int argc, char *argv[]) if (!motortest) { if (g_mk == nullptr) { - if (bus == -1) { - bus = mk_check_for_i2c_esc_bus(devicepath, motorcount); - - - } - - if (bus != -1) { - if (mk_start(bus, motorcount, devicepath) != OK) { - errx(1, "failed to start the MK-BLCtrl driver"); - } - } else { - errx(1, "failed to start the MK-BLCtrl driver (cannot find i2c esc's)"); - } + if (mk_start(motorcount, devicepath) != OK) { + errx(1, "failed to start the MK-BLCtrl driver"); + } /* parameter set ? */ if (newMode) { From 94b162d0e076a872af9d1b1538d7f688d51bfef0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Feb 2014 09:34:21 +0100 Subject: [PATCH 23/87] Fixed up nullptr handling --- src/drivers/mkblctrl/mkblctrl.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index d1c817cf31..46f7905fff 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -1176,8 +1176,11 @@ mk_start(unsigned motors, char *device_path) // try i2c3 first g_mk = new MK(3, device_path); - if (g_mk && OK == g_mk->init(motors)) { - fprintf(stderr, "[mkblctrl] scanning i2c3...\n"); + if (!g_mk) + return -ENOMEM; + + if (OK == g_mk->init(motors)) { + warnx("[mkblctrl] scanning i2c3...\n"); ret = g_mk->mk_check_for_blctrl(8, false, true); if (ret > 0) { return OK; @@ -1190,8 +1193,11 @@ mk_start(unsigned motors, char *device_path) // fallback to bus 1 g_mk = new MK(1, device_path); - if (g_mk && OK == g_mk->init(motors)) { - fprintf(stderr, "[mkblctrl] scanning i2c1...\n"); + if (!g_mk) + return -ENOMEM; + + if (OK == g_mk->init(motors)) { + warnx("[mkblctrl] scanning i2c1...\n"); ret = g_mk->mk_check_for_blctrl(8, false, true); if (ret > 0) { return OK; @@ -1201,7 +1207,7 @@ mk_start(unsigned motors, char *device_path) delete g_mk; g_mk = nullptr; - return -ENOMEM; + return -ENXIO; } From 399d59483ede8a6c7c66c3d56f3025e1650d665e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Feb 2014 09:36:22 +0100 Subject: [PATCH 24/87] Fixed code style --- src/drivers/mkblctrl/mkblctrl.cpp | 107 ++++++++++++++++-------------- 1 file changed, 57 insertions(+), 50 deletions(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index 46f7905fff..ec5f77d747 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -291,23 +291,23 @@ MK::init(unsigned motors) usleep(500000); - if (sizeof(_device) > 0) { - ret = register_driver(_device, &fops, 0666, (void *)this); + if (sizeof(_device) > 0) { + ret = register_driver(_device, &fops, 0666, (void *)this); - if (ret == OK) { + if (ret == OK) { log("creating alternate output device"); _primary_pwm_device = true; } - } + } /* start the IO interface task */ _task = task_spawn_cmd("mkblctrl", - SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 20, - 2048, - (main_t)&MK::task_main_trampoline, - nullptr); + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 20, + 2048, + (main_t)&MK::task_main_trampoline, + nullptr); if (_task < 0) { @@ -556,7 +556,7 @@ MK::task_main() } } - if(!_overrideSecurityChecks) { + if (!_overrideSecurityChecks) { /* don't go under BLCTRL_MIN_VALUE */ if (outputs.output[i] < BLCTRL_MIN_VALUE) { @@ -612,21 +612,24 @@ MK::task_main() esc.esc[i].esc_current = (uint16_t) Motor[i].Current; esc.esc[i].esc_rpm = (uint16_t) 0; esc.esc[i].esc_setpoint = (float) Motor[i].SetPoint_PX4; + if (Motor[i].Version == 1) { // BLCtrl 2.0 (11Bit) - esc.esc[i].esc_setpoint_raw = (uint16_t) (Motor[i].SetPoint<<3) | Motor[i].SetPointLowerBits; + esc.esc[i].esc_setpoint_raw = (uint16_t)(Motor[i].SetPoint << 3) | Motor[i].SetPointLowerBits; + } else { // BLCtrl < 2.0 (8Bit) esc.esc[i].esc_setpoint_raw = (uint16_t) Motor[i].SetPoint; } + esc.esc[i].esc_temperature = (uint16_t) Motor[i].Temperature; esc.esc[i].esc_state = (uint16_t) Motor[i].State; esc.esc[i].esc_errorcount = (uint16_t) 0; - // if motortest is requested - do it... - if (_motortest == true) { - mk_servo_test(i); - } + // if motortest is requested - do it... + if (_motortest == true) { + mk_servo_test(i); + } } @@ -665,7 +668,7 @@ MK::mk_servo_arm(bool status) unsigned int MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C) { - if(initI2C) { + if (initI2C) { I2C::init(); } @@ -718,8 +721,8 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C) fprintf(stderr, "[mkblctrl] blctrl[%i] : found=%i\tversion=%i\tcurrent=%i\tmaxpwm=%i\ttemperature=%i\n", i, Motor[i].State, Motor[i].Version, Motor[i].Current, Motor[i].MaxPWM, Motor[i].Temperature); } - - if(!_overrideSecurityChecks) { + + if (!_overrideSecurityChecks) { if (foundMotorCount != 4 && foundMotorCount != 6 && foundMotorCount != 8) { _task_should_exit = true; } @@ -748,8 +751,8 @@ MK::mk_servo_set(unsigned int chan, short val) tmpVal = 0; } - Motor[chan].SetPoint = (uint8_t)(tmpVal>>3)&0xff; - Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal%8)&0x07; + Motor[chan].SetPoint = (uint8_t)(tmpVal >> 3) & 0xff; + Motor[chan].SetPointLowerBits = ((uint8_t)tmpVal % 8) & 0x07; if (_armed == false) { Motor[chan].SetPoint = 0; @@ -1003,6 +1006,7 @@ MK::pwm_ioctl(file *filp, int cmd, unsigned long arg) if (arg < 2150) { Motor[cmd - PWM_SERVO_SET(0)].RawPwmValue = (unsigned short)arg; mk_servo_set(cmd - PWM_SERVO_SET(0), scaling(arg, 1010, 2100, 0, 2047)); + } else { ret = -EINVAL; } @@ -1173,19 +1177,20 @@ mk_start(unsigned motors, char *device_path) { int ret; - // try i2c3 first - g_mk = new MK(3, device_path); + // try i2c3 first + g_mk = new MK(3, device_path); - if (!g_mk) - return -ENOMEM; + if (!g_mk) + return -ENOMEM; - if (OK == g_mk->init(motors)) { - warnx("[mkblctrl] scanning i2c3...\n"); - ret = g_mk->mk_check_for_blctrl(8, false, true); - if (ret > 0) { - return OK; - } - } + if (OK == g_mk->init(motors)) { + warnx("[mkblctrl] scanning i2c3...\n"); + ret = g_mk->mk_check_for_blctrl(8, false, true); + + if (ret > 0) { + return OK; + } + } delete g_mk; g_mk = nullptr; @@ -1194,15 +1199,16 @@ mk_start(unsigned motors, char *device_path) g_mk = new MK(1, device_path); if (!g_mk) - return -ENOMEM; + return -ENOMEM; - if (OK == g_mk->init(motors)) { - warnx("[mkblctrl] scanning i2c1...\n"); - ret = g_mk->mk_check_for_blctrl(8, false, true); - if (ret > 0) { - return OK; - } - } + if (OK == g_mk->init(motors)) { + warnx("[mkblctrl] scanning i2c1...\n"); + ret = g_mk->mk_check_for_blctrl(8, false, true); + + if (ret > 0) { + return OK; + } + } delete g_mk; g_mk = nullptr; @@ -1298,16 +1304,16 @@ mkblctrl_main(int argc, char *argv[]) fprintf(stderr, "Motortest:\n"); fprintf(stderr, "First you have to start mkblctrl, the you can enter Motortest Mode with:\n"); fprintf(stderr, "mkblctrl -t\n"); - fprintf(stderr, "This will spin up once every motor in order of motoraddress. (DANGER !!!)\n"); + fprintf(stderr, "This will spin up once every motor in order of motoraddress. (DANGER !!!)\n"); exit(1); } if (!motortest) { if (g_mk == nullptr) { - if (mk_start(motorcount, devicepath) != OK) { - errx(1, "failed to start the MK-BLCtrl driver"); - } + if (mk_start(motorcount, devicepath) != OK) { + errx(1, "failed to start the MK-BLCtrl driver"); + } /* parameter set ? */ if (newMode) { @@ -1316,18 +1322,19 @@ mkblctrl_main(int argc, char *argv[]) } exit(0); + } else { errx(1, "MK-BLCtrl driver already running"); } } else { - if (g_mk == nullptr) { - errx(1, "MK-BLCtrl driver not running. You have to start it first."); + if (g_mk == nullptr) { + errx(1, "MK-BLCtrl driver not running. You have to start it first."); - } else { - g_mk->set_motor_test(motortest); - exit(0); + } else { + g_mk->set_motor_test(motortest); + exit(0); - } - } + } + } } From 080b2da214e014933e9062aca9a0be5bd1a2340a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Feb 2014 14:23:48 +0100 Subject: [PATCH 25/87] Updated uploader from Bootloader repo --- Tools/px_uploader.py | 48 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index cce5e5e54a..23dc484505 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -50,6 +50,9 @@ # Currently only used for informational purposes. # +# for python2.7 compatibility +from __future__ import print_function + import sys import argparse import binascii @@ -154,6 +157,8 @@ class uploader(object): PROG_MULTI = b'\x27' READ_MULTI = b'\x28' # rev2 only GET_CRC = b'\x29' # rev3+ + GET_OTP = b'\x2a' # rev4+ , get a word from OTP area + GET_SN = b'\x2b' # rev4+ , get a word from SN area REBOOT = b'\x30' INFO_BL_REV = b'\x01' # bootloader protocol revision @@ -175,6 +180,8 @@ class uploader(object): def __init__(self, portname, baudrate): # open the port, keep the default timeout short so we can poll quickly self.port = serial.Serial(portname, baudrate, timeout=0.5) + self.otp = b'' + self.sn = b'' def close(self): if self.port is not None: @@ -237,6 +244,22 @@ class uploader(object): self.__getSync() return value + # send the GET_OTP command and wait for an info parameter + def __getOTP(self, param): + t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array. + self.__send(uploader.GET_OTP + t + uploader.EOC) + value = self.__recv(4) + self.__getSync() + return value + + # send the GET_OTP command and wait for an info parameter + def __getSN(self, param): + t = struct.pack("I", param) # int param as 32bit ( 4 byte ) char array. + self.__send(uploader.GET_SN + t + uploader.EOC) + value = self.__recv(4) + self.__getSync() + return value + # send the CHIP_ERASE command and wait for the bootloader to become ready def __erase(self): self.__send(uploader.CHIP_ERASE @@ -353,6 +376,31 @@ class uploader(object): if self.fw_maxsize < fw.property('image_size'): raise RuntimeError("Firmware image is too large for this board") + # OTP added in v4: + if self.bl_rev > 3: + for byte in range(0,32*6,4): + x = self.__getOTP(byte) + self.otp = self.otp + x + print(binascii.hexlify(x).decode('utf-8') + ' ', end='') + # see src/modules/systemlib/otp.h in px4 code: + self.otp_id = self.otp[0:4] + self.otp_idtype = self.otp[4:5] + self.otp_vid = self.otp[8:4:-1] + self.otp_pid = self.otp[12:8:-1] + self.otp_coa = self.otp[32:160] + # show user: + print("type: " + self.otp_id.decode('utf-8')) + print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('utf-8')) + print("vid: " + binascii.hexlify(self.otp_vid).decode('utf-8')) + print("pid: "+ binascii.hexlify(self.otp_pid).decode('utf-8')) + print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('utf-8')) + print("sn: ", end='') + for byte in range(0,12,4): + x = self.__getSN(byte) + x = x[::-1] # reverse the bytes + self.sn = self.sn + x + print(binascii.hexlify(x).decode('utf-8'), end='') # show user + print('') print("erase...") self.__erase() From 70e1bfa4d69e967b309d177060804e7567f148b2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 7 Feb 2014 22:28:42 +0100 Subject: [PATCH 26/87] Startup scripts: use rc.mc_defaults for default MC parameters --- .../px4fmu_common/init.d/10015_tbs_discovery | 41 +--------------- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 38 +-------------- ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil | 4 +- ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil | 4 +- ROMFS/px4fmu_common/init.d/12001_octo_cox | 4 +- ROMFS/px4fmu_common/init.d/4001_quad_x | 44 +---------------- ROMFS/px4fmu_common/init.d/4010_dji_f330 | 47 +------------------ ROMFS/px4fmu_common/init.d/4011_dji_f450 | 47 +------------------ ROMFS/px4fmu_common/init.d/4012_hk_x550 | 6 --- ROMFS/px4fmu_common/init.d/5001_quad_+ | 4 +- ROMFS/px4fmu_common/init.d/6001_hexa_x | 4 +- ROMFS/px4fmu_common/init.d/7001_hexa_+ | 6 ++- ROMFS/px4fmu_common/init.d/8001_octo_x | 4 +- ROMFS/px4fmu_common/init.d/9001_octo_+ | 4 +- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 45 ++++++++++++++++++ 15 files changed, 79 insertions(+), 223 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index a3d7c3d977..b09765e8e7 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -5,45 +5,8 @@ # Simon Wilks # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ROLL_P 5.0 - param set MC_ROLLRATE_P 0.17 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.006 - param set MC_PITCH_P 5.0 - param set MC_PITCHRATE_P 0.17 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.006 - param set MC_YAW_P 0.5 - param set MC_YAWRATE_P 0.2 - param set MC_YAWRATE_I 0.0 - param set MC_YAWRATE_D 0.0 +sh /etc/init.d/rc.mc_defaults - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 -fi - -set VEHICLE_TYPE mc set MIXER FMU_quad_w -set PWM_OUTPUTS 1234 -set PWM_RATE 400 +set PWM_OUTPUTS 1234 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 1c7ecb7129..42d5169935 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -5,51 +5,17 @@ # Anton Babushkin # +sh /etc/init.d/rc.mc_defaults + if [ $DO_AUTOCONFIG == yes ] then # # Default parameters for this platform # - param set MC_ROLL_P 9.0 - param set MC_ROLLRATE_P 0.13 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 9.0 - param set MC_PITCHRATE_P 0.13 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 0.5 - param set MC_YAWRATE_P 0.2 - param set MC_YAWRATE_I 0.0 - param set MC_YAWRATE_D 0.0 - - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 - param set BAT_V_SCALING 0.00989 param set BAT_C_SCALING 0.0124 fi -set VEHICLE_TYPE mc set MIXER FMU_quad_w set PWM_OUTPUTS 1234 -set PWM_RATE 400 -set PWM_DISARMED 900 -set PWM_MIN 1000 -set PWM_MAX 2000 diff --git a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil index 45880f44be..7a7a9542c0 100644 --- a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil +++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil @@ -5,6 +5,8 @@ # Anton Babushkin # -sh /etc/init.d/4001_quad_x +sh /etc/init.d/rc.mc_defaults + +set MIXER FMU_quad_x set HIL yes diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil index 2b26810e71..c47500c7ac 100644 --- a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil +++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil @@ -5,6 +5,8 @@ # Anton Babushkin # -sh /etc/init.d/1001_rc_quad_x.hil +sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_+ + +set HIL yes \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox index 8a813595e4..c5d3e78078 100644 --- a/ROMFS/px4fmu_common/init.d/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox @@ -5,6 +5,8 @@ # Lorenz Meier , Anton Babushkin # -sh /etc/init.d/8001_octo_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_cox + +set PWM_OUTPUTS 12345678 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x index 0f1288dec3..fa751f1e31 100644 --- a/ROMFS/px4fmu_common/init.d/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/4001_quad_x @@ -5,48 +5,8 @@ # Lorenz Meier # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.12 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.12 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 -fi +sh /etc/init.d/rc.mc_defaults -set VEHICLE_TYPE mc set MIXER FMU_quad_x -set PWM_OUTPUTS 1234 -set PWM_RATE 400 -set PWM_DISARMED 900 -set PWM_MIN 1100 -set PWM_MAX 2000 +set PWM_OUTPUTS 1234 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 7829460339..232af57b4a 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -5,49 +5,6 @@ # Anton Babushkin # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.12 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.12 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.8 - param set MC_YAWRATE_P 0.2 - param set MC_YAWRATE_I 0.05 - param set MC_YAWRATE_D 0.0 - - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 -fi +sh /etc/init.d/4001_quad_x -set VEHICLE_TYPE mc -set MIXER FMU_quad_x - -set PWM_OUTPUTS 1234 -set PWM_RATE 400 -# DJI ESC range -set PWM_DISARMED 900 -set PWM_MIN 1200 -set PWM_MAX 1900 +set PWM_MIN 1175 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 8eb53d1720..259636acc2 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -5,49 +5,6 @@ # Lorenz Meier # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.12 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.12 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 -fi +sh /etc/init.d/4001_quad_x -set VEHICLE_TYPE mc -set MIXER FMU_quad_x - -set PWM_OUTPUTS 1234 -set PWM_RATE 400 -# DJI ESC range -set PWM_DISARMED 900 -set PWM_MIN 1200 -set PWM_MAX 1900 +set PWM_MIN 1175 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550 index 3d8e9fcf70..a5c4a86902 100644 --- a/ROMFS/px4fmu_common/init.d/4012_hk_x550 +++ b/ROMFS/px4fmu_common/init.d/4012_hk_x550 @@ -6,9 +6,3 @@ # sh /etc/init.d/4001_quad_x - -set PWM_OUTPUTS 1234 -set PWM_RATE 400 -set PWM_DISARMED 900 -set PWM_MIN 1000 -set PWM_MAX 2000 diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+ index ff11bccfe6..2f5ab44d77 100644 --- a/ROMFS/px4fmu_common/init.d/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/5001_quad_+ @@ -5,6 +5,8 @@ # Anton Babushkin # -sh /etc/init.d/4001_quad_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_+ + +set PWM_OUTPUTS 1234 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x index fd57565860..73ef12569b 100644 --- a/ROMFS/px4fmu_common/init.d/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x @@ -5,10 +5,10 @@ # Anton Babushkin # -sh /etc/init.d/4001_quad_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_x # We only can run one channel group with one rate, # so all 8 at 400 Hz -set PWM_OUTPUTS 12345678 +set PWM_OUTPUTS 12345678 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ index 45279ec390..ef4b6297de 100644 --- a/ROMFS/px4fmu_common/init.d/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ @@ -5,6 +5,10 @@ # Anton Babushkin # -sh /etc/init.d/6001_hexa_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_+ + +# We only can run one channel group with one rate, +# so all 8 at 400 Hz +set PWM_OUTPUTS 12345678 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x index 6fa9626684..bb87f89fe7 100644 --- a/ROMFS/px4fmu_common/init.d/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/8001_octo_x @@ -5,8 +5,8 @@ # Anton Babushkin # -sh /etc/init.d/4001_quad_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_x -set PWM_OUTPUTS 12345678 +set PWM_OUTPUTS 12345678 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+ index fa3869f9f9..81132fd3e7 100644 --- a/ROMFS/px4fmu_common/init.d/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/9001_octo_+ @@ -5,6 +5,8 @@ # Anton Babushkin # -sh /etc/init.d/8001_octo_x +sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_+ + +set PWM_OUTPUTS 12345678 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults new file mode 100644 index 0000000000..14b6fe12cb --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -0,0 +1,45 @@ +#!nsh + +set VEHICLE_TYPE mc + +if [ $DO_AUTOCONFIG == yes ] +then + # + # Default parameters for this platform + # + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.12 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.004 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.12 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.004 + param set MC_YAW_P 2.0 + param set MC_YAWRATE_P 0.3 + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_D 0.005 + + param set MPC_THR_MAX 1.0 + param set MPC_THR_MIN 0.1 + param set MPC_XY_P 1.0 + param set MPC_XY_VEL_P 0.1 + param set MPC_XY_VEL_I 0.02 + param set MPC_XY_VEL_D 0.01 + param set MPC_XY_VEL_MAX 5 + param set MPC_XY_FF 0.5 + param set MPC_Z_P 1.0 + param set MPC_Z_VEL_P 0.1 + param set MPC_Z_VEL_I 0.02 + param set MPC_Z_VEL_D 0.0 + param set MPC_Z_VEL_MAX 3 + param set MPC_Z_FF 0.5 + param set MPC_TILT_MAX 1.0 + param set MPC_LAND_SPEED 1.0 + param set MPC_LAND_TILT 0.3 +fi + +set PWM_RATE 400 +set PWM_DISARMED 900 +set PWM_MIN 1075 +set PWM_MAX 2000 \ No newline at end of file From fff00318cdeac8b52affb2210dd0975c65826333 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 7 Feb 2014 22:39:06 +0100 Subject: [PATCH 27/87] Startup scripts: get the indentation right --- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 68 +++++++++++------------ 1 file changed, 34 insertions(+), 34 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 14b6fe12cb..13b2c97174 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -1,42 +1,42 @@ #!nsh -set VEHICLE_TYPE mc +set VEHICLE_TYPE fw if [ $DO_AUTOCONFIG == yes ] then - # - # Default parameters for this platform - # - param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.12 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.12 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - - param set MPC_THR_MAX 1.0 - param set MPC_THR_MIN 0.1 - param set MPC_XY_P 1.0 - param set MPC_XY_VEL_P 0.1 - param set MPC_XY_VEL_I 0.02 - param set MPC_XY_VEL_D 0.01 - param set MPC_XY_VEL_MAX 5 - param set MPC_XY_FF 0.5 - param set MPC_Z_P 1.0 - param set MPC_Z_VEL_P 0.1 - param set MPC_Z_VEL_I 0.02 - param set MPC_Z_VEL_D 0.0 - param set MPC_Z_VEL_MAX 3 - param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 - param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 + # + # Default parameters for this platform + # + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.12 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.004 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.12 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.004 + param set MC_YAW_P 2.0 + param set MC_YAWRATE_P 0.3 + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_D 0.005 + + param set MPC_THR_MAX 1.0 + param set MPC_THR_MIN 0.1 + param set MPC_XY_P 1.0 + param set MPC_XY_VEL_P 0.1 + param set MPC_XY_VEL_I 0.02 + param set MPC_XY_VEL_D 0.01 + param set MPC_XY_VEL_MAX 5 + param set MPC_XY_FF 0.5 + param set MPC_Z_P 1.0 + param set MPC_Z_VEL_P 0.1 + param set MPC_Z_VEL_I 0.02 + param set MPC_Z_VEL_D 0.0 + param set MPC_Z_VEL_MAX 3 + param set MPC_Z_FF 0.5 + param set MPC_TILT_MAX 1.0 + param set MPC_LAND_SPEED 1.0 + param set MPC_LAND_TILT 0.3 fi set PWM_RATE 400 From df41c04be74c6d4d576c188f2327226c264d371c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 7 Feb 2014 23:13:12 +0100 Subject: [PATCH 28/87] Startup scripts: use rc.fw_defaults for default FW parameters --- .../init.d/1000_rc_fw_easystar.hil | 30 +---------- .../init.d/1004_rc_fw_Rascal110.hil | 32 +---------- .../init.d/1005_rc_fw_Malolo1.hil | 53 +------------------ ROMFS/px4fmu_common/init.d/2100_mpx_easystar | 33 +----------- ROMFS/px4fmu_common/init.d/2101_hk_bixler | 32 +---------- ROMFS/px4fmu_common/init.d/2102_3dr_skywalker | 30 +---------- ROMFS/px4fmu_common/init.d/3030_io_camflyer | 35 +----------- ROMFS/px4fmu_common/init.d/3031_phantom | 36 ------------- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 35 +----------- ROMFS/px4fmu_common/init.d/3033_wingwing | 35 +----------- ROMFS/px4fmu_common/init.d/3034_fx79 | 35 +----------- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 35 ++++++++++++ 12 files changed, 47 insertions(+), 374 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/rc.fw_defaults diff --git a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil index d7e524b414..36194ad682 100644 --- a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil +++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil @@ -5,36 +5,10 @@ # Lorenz Meier # -echo "HIL Rascal 110 starting.." +sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == yes ] -then - # Set all params here, then disable autoconfig - - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 16 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +echo "HIL Rascal 110 starting.." set HIL yes -set VEHICLE_TYPE fw set MIXER FMU_AERT diff --git a/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil b/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil index c639bfc254..4e3e183262 100644 --- a/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil +++ b/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil @@ -5,38 +5,10 @@ # Thomas Gubler # -echo "HIL Rascal 110 starting.." +sh /etc/init.d/rc.fw_defaults -if [ $DO_AUTOCONFIG == yes ] -then - # Set all params here, then disable autoconfig - - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 16 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +echo "HIL Rascal 110 starting.." set HIL yes -set VEHICLE_TYPE fw set MIXER FMU_AERT diff --git a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil index 124bf63abf..abbe626b13 100644 --- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil +++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil @@ -5,60 +5,9 @@ # Thomas Gubler # -echo "HIL Malolo 1 starting.." - -if [ $DO_AUTOCONFIG == yes ] -then - # Set all params here, then disable autoconfig - - param set FW_AIRSPD_MIN 12 - param set FW_AIRSPD_TRIM 25 - param set FW_ATT_TC 0.3 - param set FW_L1_DAMPING 0.74 - param set FW_L1_PERIOD 15 - param set FW_PR_FF 0.8 - param set FW_PR_I 0.05 - param set FW_PR_IMAX 0.2 - param set FW_PR_P 0.1 - param set FW_P_LIM_MAX 45 - param set FW_P_LIM_MIN -45 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 0 - param set FW_RR_FF 0.6 - param set FW_RR_I 0.02 - param set FW_RR_IMAX 0.2 - param set FW_RR_P 0.1 - param set FW_R_LIM 45 - param set FW_R_RMAX 0 - param set FW_THR_CRUISE 0.6 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0 - param set FW_T_CLMB_MAX 5 - param set FW_T_HRATE_P 0.02 - param set FW_T_PTCH_DAMP 0 - param set FW_T_RLL2THR 15 - param set FW_T_SINK_MAX 5 - param set FW_T_SINK_MIN 2 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 3 - param set FW_T_VERT_ACC 7 - param set FW_YCO_VMIN 1000 - param set FW_YR_FF 0.0 - param set FW_YR_I 0 - param set FW_YR_IMAX 0.2 - param set FW_YR_P 0.0 - param set FW_Y_RMAX 0 - param set NAV_LAND_ALT 90 - param set NAV_RTL_ALT 100 - param set NAV_RTL_LAND_T -1 - - param set SYS_AUTOCONFIG 0 - param save -fi +sh /etc/init.d/rc.fw_defaults set HIL yes -set VEHICLE_TYPE fw # Set the AERT mixer for HIL (even if the malolo is a flying wing) set MIXER FMU_AERT diff --git a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar index 0e5bf60d60..465a22c53a 100644 --- a/ROMFS/px4fmu_common/init.d/2100_mpx_easystar +++ b/ROMFS/px4fmu_common/init.d/2100_mpx_easystar @@ -2,38 +2,7 @@ # # MPX EasyStar Plane # -# Maintainers: ??? -# -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 16 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_RET diff --git a/ROMFS/px4fmu_common/init.d/2101_hk_bixler b/ROMFS/px4fmu_common/init.d/2101_hk_bixler index de5e5a8d3a..dcc5db824a 100644 --- a/ROMFS/px4fmu_common/init.d/2101_hk_bixler +++ b/ROMFS/px4fmu_common/init.d/2101_hk_bixler @@ -1,35 +1,5 @@ #!nsh -if [ $DO_AUTOCONFIG == yes ] -then - # Set all params here, then disable autoconfig - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 16 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 - - param set SYS_AUTOCONFIG 0 - param save -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_AERT \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker b/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker index 07f215f6cf..dcc5db824a 100644 --- a/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker +++ b/ROMFS/px4fmu_common/init.d/2102_3dr_skywalker @@ -1,33 +1,5 @@ #!nsh -if [ $DO_AUTOCONFIG == yes ] -then - # Set all params here, then disable autoconfig - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 100 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.65 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_Y_ROLLFF 1.1 - param set FW_L1_PERIOD 16 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 - - param set SYS_AUTOCONFIG 0 - param save -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_AERT \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer index 3b7323ac4e..83c470234c 100644 --- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer @@ -1,38 +1,5 @@ #!nsh -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_AIRSPD_MIN 7 - param set FW_AIRSPD_TRIM 9 - param set FW_AIRSPD_MAX 14 - param set FW_L1_PERIOD 10 - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 20 - param set FW_P_LIM_MAX 30 - param set FW_P_LIM_MIN -20 - param set FW_P_P 30 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 2 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 60 - param set FW_R_RMAX 60 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 1.0 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5 - param set FW_T_SINK_MIN 2 - param set FW_T_TIME_CONST 9 - param set FW_Y_ROLLFF 2.0 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_Q diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index a4ff61d937..2e2434bb85 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -5,40 +5,4 @@ # Simon Wilks # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_AIRSPD_MIN 11.4 - param set FW_AIRSPD_TRIM 14 - param set FW_AIRSPD_MAX 22 - param set FW_L1_PERIOD 15 - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 45 - param set FW_P_LIM_MIN -45 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 2 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 15 - param set FW_R_P 80 - param set FW_R_RMAX 60 - param set FW_THR_CRUISE 0.8 - param set FW_THR_LND_MAX 0 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0.5 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 2.0 - param set FW_Y_ROLLFF 1.0 - param set RC_SCALE_ROLL 0.6 - param set RC_SCALE_PITCH 0.6 - param set TRIM_PITCH 0.1 -fi - -set VEHICLE_TYPE fw set MIXER FMU_Q diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index c1e78b6f1e..1657e6d368 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -5,39 +5,6 @@ # Thomas Gubler , Julian Oes # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_AIRSPD_MIN 7 - param set FW_AIRSPD_TRIM 9 - param set FW_AIRSPD_MAX 14 - param set FW_L1_PERIOD 10 - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 20 - param set FW_P_LIM_MAX 30 - param set FW_P_LIM_MIN -20 - param set FW_P_P 30 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 2 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 60 - param set FW_R_RMAX 60 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 0.7 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5 - param set FW_T_SINK_MIN 2 - param set FW_T_TIME_CONST 9 - param set FW_Y_ROLLFF 2.0 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_X5 diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index 2f68797999..2af3618d98 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -5,39 +5,6 @@ # Simon Wilks # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_AIRSPD_MIN 7 - param set FW_AIRSPD_TRIM 9 - param set FW_AIRSPD_MAX 14 - param set FW_L1_PERIOD 10 - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 20 - param set FW_P_LIM_MAX 30 - param set FW_P_LIM_MIN -20 - param set FW_P_P 30 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 2 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 60 - param set FW_R_RMAX 60 - param set FW_THR_CRUISE 0.65 - param set FW_THR_MAX 0.7 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5 - param set FW_T_SINK_MIN 2 - param set FW_T_TIME_CONST 9 - param set FW_Y_ROLLFF 2.0 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_Q diff --git a/ROMFS/px4fmu_common/init.d/3034_fx79 b/ROMFS/px4fmu_common/init.d/3034_fx79 index bc02d87f3d..f4bd18269d 100644 --- a/ROMFS/px4fmu_common/init.d/3034_fx79 +++ b/ROMFS/px4fmu_common/init.d/3034_fx79 @@ -5,39 +5,6 @@ # Simon Wilks # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set FW_AIRSPD_MAX 20 - param set FW_AIRSPD_TRIM 12 - param set FW_AIRSPD_MIN 15 - param set FW_L1_PERIOD 12 - param set FW_P_D 0 - param set FW_P_I 0 - param set FW_P_IMAX 15 - param set FW_P_LIM_MAX 50 - param set FW_P_LIM_MIN -50 - param set FW_P_P 60 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 1.1 - param set FW_R_D 0 - param set FW_R_I 5 - param set FW_R_IMAX 20 - param set FW_R_P 80 - param set FW_R_RMAX 100 - param set FW_THR_CRUISE 0.75 - param set FW_THR_MAX 1 - param set FW_THR_MIN 0 - param set FW_T_SINK_MAX 5.0 - param set FW_T_SINK_MIN 4.0 - param set FW_T_TIME_CONST 9 - param set FW_Y_ROLLFF 1.1 - param set RC_SCALE_ROLL 1.0 - param set RC_SCALE_PITCH 1.0 -fi +sh /etc/init.d/rc.fw_defaults -set VEHICLE_TYPE fw set MIXER FMU_FX79 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults new file mode 100644 index 0000000000..0de13af070 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -0,0 +1,35 @@ +#!nsh + +set VEHICLE_TYPE fw + +if [ $DO_AUTOCONFIG == yes ] +then +# +# Default parameters for this platform +# + param set FW_AIRSPD_MIN 15 + param set FW_AIRSPD_TRIM 20 + param set FW_AIRSPD_MAX 80 + param set FW_ATT_TC 0.3 + param set FW_L1_DAMPING 0.74 + param set FW_L1_PERIOD 15 + param set FW_PR_FF 0.8 + param set FW_PR_I 0 + param set FW_PR_IMAX 0.2 + param set FW_PR_P 0.05 + param set FW_P_LIM_MAX 45 + param set FW_P_LIM_MIN -45 + param set FW_P_RMAX_NEG 0 + param set FW_P_RMAX_POS 0 + param set FW_P_ROLLFF 0 + param set FW_RR_FF 0.6 + param set FW_RR_I 0 + param set FW_RR_IMAX 0.2 + param set FW_RR_P 0.05 + param set FW_R_LIM 60 + param set FW_R_RMAX 0 + param set FW_T_HRATE_P 0.01 + param set FW_T_RLL2THR 15 + param set FW_T_SRATE_P 0.01 + param set FW_T_TIME_CONST 5 +fi \ No newline at end of file From ac653416f8f5163a4f162ab431d69129c9e1858e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 7 Feb 2014 22:13:20 +0100 Subject: [PATCH 29/87] X5: copy content of FMU_Q.mix to FMU_X5.mix because FMU_Q was used previously by the X5 startup script --- ROMFS/px4fmu_common/mixers/FMU_X5.mix | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/FMU_X5.mix b/ROMFS/px4fmu_common/mixers/FMU_X5.mix index 6108683549..80e3bac09c 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_X5.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_X5.mix @@ -23,13 +23,13 @@ for the elevons. M: 2 O: 10000 10000 0 -10000 10000 -S: 0 0 -3000 -5000 0 -10000 10000 -S: 0 1 -5000 -5000 0 -10000 10000 +S: 0 0 -8000 -8000 0 -10000 10000 +S: 0 1 6000 6000 0 -10000 10000 M: 2 O: 10000 10000 0 -10000 10000 -S: 0 0 -5000 -3000 0 -10000 10000 -S: 0 1 5000 5000 0 -10000 10000 +S: 0 0 -8000 -8000 0 -10000 10000 +S: 0 1 -6000 -6000 0 -10000 10000 Output 2 -------- @@ -48,7 +48,7 @@ M: 1 O: 10000 10000 0 -10000 10000 S: 0 3 0 20000 -10000 -10000 10000 -Gimbal / payload mixer for last four channels +Gimbal / flaps / payload mixer for last four channels ----------------------------------------------------- M: 1 @@ -66,4 +66,3 @@ S: 0 6 10000 10000 0 -10000 10000 M: 1 O: 10000 10000 0 -10000 10000 S: 0 7 10000 10000 0 -10000 10000 - From 008a973ef7de6433d3215df5cc8f553ce494ba22 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 7 Feb 2014 23:51:57 +0100 Subject: [PATCH 30/87] Startup scripts: get the indentation right, take 2 --- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 50 +++++++++++------------ 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 0de13af070..cbf0ba4000 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -7,29 +7,29 @@ then # # Default parameters for this platform # - param set FW_AIRSPD_MIN 15 - param set FW_AIRSPD_TRIM 20 - param set FW_AIRSPD_MAX 80 - param set FW_ATT_TC 0.3 - param set FW_L1_DAMPING 0.74 - param set FW_L1_PERIOD 15 - param set FW_PR_FF 0.8 - param set FW_PR_I 0 - param set FW_PR_IMAX 0.2 - param set FW_PR_P 0.05 - param set FW_P_LIM_MAX 45 - param set FW_P_LIM_MIN -45 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 0 - param set FW_RR_FF 0.6 - param set FW_RR_I 0 - param set FW_RR_IMAX 0.2 - param set FW_RR_P 0.05 - param set FW_R_LIM 60 - param set FW_R_RMAX 0 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 + param set FW_AIRSPD_MIN 15 + param set FW_AIRSPD_TRIM 20 + param set FW_AIRSPD_MAX 80 + param set FW_ATT_TC 0.3 + param set FW_L1_DAMPING 0.74 + param set FW_L1_PERIOD 15 + param set FW_PR_FF 0.8 + param set FW_PR_I 0 + param set FW_PR_IMAX 0.2 + param set FW_PR_P 0.05 + param set FW_P_LIM_MAX 45 + param set FW_P_LIM_MIN -45 + param set FW_P_RMAX_NEG 0 + param set FW_P_RMAX_POS 0 + param set FW_P_ROLLFF 0 + param set FW_RR_FF 0.6 + param set FW_RR_I 0 + param set FW_RR_IMAX 0.2 + param set FW_RR_P 0.05 + param set FW_R_LIM 60 + param set FW_R_RMAX 0 + param set FW_T_HRATE_P 0.01 + param set FW_T_RLL2THR 15 + param set FW_T_SRATE_P 0.01 + param set FW_T_TIME_CONST 5 fi \ No newline at end of file From 096735897c70076ee26c1d343538eae8a585f285 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 7 Feb 2014 23:52:56 +0100 Subject: [PATCH 31/87] Startup scripts: added important LAND and RTL parameters for FW --- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index cbf0ba4000..a28f67b656 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -32,4 +32,8 @@ then param set FW_T_RLL2THR 15 param set FW_T_SRATE_P 0.01 param set FW_T_TIME_CONST 5 + + param set NAV_LAND_ALT 90 + param set NAV_RTL_ALT 100 + param set NAV_RTL_LAND_T -1 fi \ No newline at end of file From de8a9268f3c476c2695df84f0e1a429ea10ddeb3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 8 Feb 2014 00:31:53 +0100 Subject: [PATCH 32/87] Startup scripts: bring back HIL parameters for Malolo --- .../init.d/1005_rc_fw_Malolo1.hil | 34 +++++++++++++++++++ 1 file changed, 34 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil index abbe626b13..c753ded233 100644 --- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil +++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil @@ -7,6 +7,40 @@ sh /etc/init.d/rc.fw_defaults +if [ $DO_AUTOCONFIG == yes ] +then + param set FW_AIRSPD_MIN 12 + param set FW_AIRSPD_TRIM 25 + param set FW_AIRSPD_MAX 40 + param set FW_ATT_TC 0.3 + param set FW_L1_DAMPING 0.74 + param set FW_L1_PERIOD 15 + param set FW_PR_FF 0.8 + param set FW_PR_I 0.05 + param set FW_PR_IMAX 0.2 + param set FW_PR_P 0.1 + param set FW_P_ROLLFF 0 + param set FW_RR_FF 0.6 + param set FW_RR_I 0.02 + param set FW_RR_IMAX 0.2 + param set FW_RR_P 0.1 + param set FW_R_LIM 45 + param set FW_R_RMAX 0 + param set FW_T_CLMB_MAX 5 + param set FW_T_HRATE_P 0.02 + param set FW_T_PTCH_DAMP 0 + param set FW_T_RLL2THR 15 + param set FW_T_SINK_MAX 5 + param set FW_T_SINK_MIN 2 + param set FW_T_SRATE_P 0.01 + param set FW_T_TIME_CONST 3 + param set FW_T_VERT_ACC 7 + param set FW_YR_FF 0.0 + param set FW_YR_I 0 + param set FW_YR_IMAX 0.2 + param set FW_YR_P 0.0 +fi + set HIL yes # Set the AERT mixer for HIL (even if the malolo is a flying wing) From 0a87f1d01ce089e6f6ddba42be6847d5783cbfaf Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 8 Feb 2014 00:32:57 +0100 Subject: [PATCH 33/87] Startup scripts: move X5 attitude parameters back to X5 script and only leave airframe independent params in FW defaults script --- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 29 ++++++++++++++++++++ ROMFS/px4fmu_common/init.d/rc.fw_defaults | 28 +------------------ ROMFS/px4fmu_common/init.d/rc.mc_defaults | 2 +- 3 files changed, 31 insertions(+), 28 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index 1657e6d368..3f5f79857d 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -7,4 +7,33 @@ sh /etc/init.d/rc.fw_defaults +if [ $DO_AUTOCONFIG == yes ] +then + param set FW_AIRSPD_MIN 15 + param set FW_AIRSPD_TRIM 20 + param set FW_AIRSPD_MAX 40 + param set FW_ATT_TC 0.3 + param set FW_L1_DAMPING 0.74 + param set FW_L1_PERIOD 15 + param set FW_PR_FF 0.8 + param set FW_PR_I 0 + param set FW_PR_IMAX 0.2 + param set FW_PR_P 0.05 + param set FW_P_LIM_MAX 45 + param set FW_P_LIM_MIN -45 + param set FW_P_RMAX_NEG 0 + param set FW_P_RMAX_POS 0 + param set FW_P_ROLLFF 0 + param set FW_RR_FF 0.6 + param set FW_RR_I 0 + param set FW_RR_IMAX 0.2 + param set FW_RR_P 0.05 + param set FW_R_LIM 60 + param set FW_R_RMAX 0 + param set FW_T_HRATE_P 0.01 + param set FW_T_RLL2THR 15 + param set FW_T_SRATE_P 0.01 + param set FW_T_TIME_CONST 5 +fi + set MIXER FMU_X5 diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index a28f67b656..3e340699fc 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -5,34 +5,8 @@ set VEHICLE_TYPE fw if [ $DO_AUTOCONFIG == yes ] then # -# Default parameters for this platform +# Default parameters for FW # - param set FW_AIRSPD_MIN 15 - param set FW_AIRSPD_TRIM 20 - param set FW_AIRSPD_MAX 80 - param set FW_ATT_TC 0.3 - param set FW_L1_DAMPING 0.74 - param set FW_L1_PERIOD 15 - param set FW_PR_FF 0.8 - param set FW_PR_I 0 - param set FW_PR_IMAX 0.2 - param set FW_PR_P 0.05 - param set FW_P_LIM_MAX 45 - param set FW_P_LIM_MIN -45 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 - param set FW_P_ROLLFF 0 - param set FW_RR_FF 0.6 - param set FW_RR_I 0 - param set FW_RR_IMAX 0.2 - param set FW_RR_P 0.05 - param set FW_R_LIM 60 - param set FW_R_RMAX 0 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 - param set NAV_LAND_ALT 90 param set NAV_RTL_ALT 100 param set NAV_RTL_LAND_T -1 diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 13b2c97174..50d02d9e47 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -5,7 +5,7 @@ set VEHICLE_TYPE fw if [ $DO_AUTOCONFIG == yes ] then # - # Default parameters for this platform + # Default parameters for MC # param set MC_ROLL_P 7.0 param set MC_ROLLRATE_P 0.12 From 70964dd87c72b2b9bd475645654e894ba827ac64 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 9 Feb 2014 18:34:54 +0100 Subject: [PATCH 34/87] Update upload script from bootloader repo --- Tools/px_uploader.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 23dc484505..e4a8b3c054 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -381,7 +381,7 @@ class uploader(object): for byte in range(0,32*6,4): x = self.__getOTP(byte) self.otp = self.otp + x - print(binascii.hexlify(x).decode('utf-8') + ' ', end='') + print(binascii.hexlify(x).decode('Latin-1') + ' ', end='') # see src/modules/systemlib/otp.h in px4 code: self.otp_id = self.otp[0:4] self.otp_idtype = self.otp[4:5] @@ -389,17 +389,17 @@ class uploader(object): self.otp_pid = self.otp[12:8:-1] self.otp_coa = self.otp[32:160] # show user: - print("type: " + self.otp_id.decode('utf-8')) - print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('utf-8')) - print("vid: " + binascii.hexlify(self.otp_vid).decode('utf-8')) - print("pid: "+ binascii.hexlify(self.otp_pid).decode('utf-8')) - print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('utf-8')) + print("type: " + self.otp_id.decode('Latin-1')) + print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1')) + print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1')) + print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1')) + print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1')) print("sn: ", end='') for byte in range(0,12,4): x = self.__getSN(byte) x = x[::-1] # reverse the bytes self.sn = self.sn + x - print(binascii.hexlify(x).decode('utf-8'), end='') # show user + print(binascii.hexlify(x).decode('Latin-1'), end='') # show user print('') print("erase...") self.__erase() From a9e5e2e31a73e4ca546bf89e807b71187a41b657 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 10 Feb 2014 08:54:48 +0100 Subject: [PATCH 35/87] position_estimator_inav: default parameters and min/max EPH/EPV updated --- .../position_estimator_inav_main.c | 8 ++++---- .../position_estimator_inav_params.c | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index e045ce4cca..bf4f7ae974 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -527,13 +527,13 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) if (gps.fix_type >= 3) { /* hysteresis for GPS quality */ if (gps_valid) { - if (gps.eph_m > 10.0f || gps.epv_m > 10.0f) { + if (gps.eph_m > 10.0f || gps.epv_m > 20.0f) { gps_valid = false; mavlink_log_info(mavlink_fd, "[inav] GPS signal lost"); } } else { - if (gps.eph_m < 5.0f && gps.epv_m < 5.0f) { + if (gps.eph_m < 5.0f && gps.epv_m < 10.0f) { gps_valid = true; mavlink_log_info(mavlink_fd, "[inav] GPS signal found"); } @@ -589,8 +589,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) corr_gps[2][1] = 0.0f; } - w_gps_xy = 1.0f / fmaxf(1.0f, gps.eph_m); - w_gps_z = 1.0f / fmaxf(1.0f, gps.epv_m); + w_gps_xy = 2.0f / fmaxf(2.0f, gps.eph_m); + w_gps_z = 4.0f / fmaxf(4.0f, gps.epv_m); } } else { diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index e1bbd75a6e..b71f9472f5 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -40,7 +40,7 @@ #include "position_estimator_inav_params.h" -PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 1.0f); +PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f); PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f); PARAM_DEFINE_FLOAT(INAV_W_Z_ACC, 20.0f); PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); From 0dc7f223ea26a09cd538114f54d99a7ab130efba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Feb 2014 12:08:39 +1100 Subject: [PATCH 36/87] FMUv2: fixed UART3 flow control pins --- nuttx-configs/px4fmu-v2/include/board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h index e56b14ba41..850043ddf5 100755 --- a/nuttx-configs/px4fmu-v2/include/board.h +++ b/nuttx-configs/px4fmu-v2/include/board.h @@ -209,8 +209,8 @@ #define GPIO_USART3_RX GPIO_USART3_RX_3 #define GPIO_USART3_TX GPIO_USART3_TX_3 -#define GPIO_USART2_RTS GPIO_USART2_RTS_2 -#define GPIO_USART2_CTS GPIO_USART2_CTS_2 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 #define GPIO_UART4_RX GPIO_UART4_RX_1 #define GPIO_UART4_TX GPIO_UART4_TX_1 From b0c60296f58dfec02f115d0033f61e95389f5931 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Feb 2014 12:08:39 +1100 Subject: [PATCH 37/87] FMUv2: fixed UART3 flow control pins --- nuttx-configs/px4fmu-v2/include/board.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h index e56b14ba41..850043ddf5 100755 --- a/nuttx-configs/px4fmu-v2/include/board.h +++ b/nuttx-configs/px4fmu-v2/include/board.h @@ -209,8 +209,8 @@ #define GPIO_USART3_RX GPIO_USART3_RX_3 #define GPIO_USART3_TX GPIO_USART3_TX_3 -#define GPIO_USART2_RTS GPIO_USART2_RTS_2 -#define GPIO_USART2_CTS GPIO_USART2_CTS_2 +#define GPIO_USART3_RTS GPIO_USART3_RTS_2 +#define GPIO_USART3_CTS GPIO_USART3_CTS_2 #define GPIO_UART4_RX GPIO_UART4_RX_1 #define GPIO_UART4_TX GPIO_UART4_TX_1 From 0d4b5d9395e3fd668b217301d0f888fa0238998d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Feb 2014 13:15:34 +0100 Subject: [PATCH 38/87] X5: adjusted default parameters based on test flight --- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index 3f5f79857d..bf5a87068f 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -15,19 +15,19 @@ then param set FW_ATT_TC 0.3 param set FW_L1_DAMPING 0.74 param set FW_L1_PERIOD 15 - param set FW_PR_FF 0.8 + param set FW_PR_FF 0.3 param set FW_PR_I 0 param set FW_PR_IMAX 0.2 - param set FW_PR_P 0.05 + param set FW_PR_P 0.03 param set FW_P_LIM_MAX 45 param set FW_P_LIM_MIN -45 param set FW_P_RMAX_NEG 0 param set FW_P_RMAX_POS 0 param set FW_P_ROLLFF 0 - param set FW_RR_FF 0.6 + param set FW_RR_FF 0.3 param set FW_RR_I 0 param set FW_RR_IMAX 0.2 - param set FW_RR_P 0.05 + param set FW_RR_P 0.03 param set FW_R_LIM 60 param set FW_R_RMAX 0 param set FW_T_HRATE_P 0.01 From 75d08826389680e55543eb017683c8cf9434bf7c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Feb 2014 13:16:02 +0100 Subject: [PATCH 39/87] fw_pos_control: added default for autoland parameters --- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index ee8721ff92..a0447d90d2 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -168,9 +168,9 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); -PARAM_DEFINE_FLOAT(FW_LND_ANG, 10.0f); +PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); -PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f); +PARAM_DEFINE_FLOAT(FW_LND_FLALT, 10.0f); PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f); PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); From 44bde0db912c78f5a9d7d71f974dd2f36873dd24 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Feb 2014 13:16:27 +0100 Subject: [PATCH 40/87] Navgitor: adjusted default loiter radius --- src/modules/navigator/navigator_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index d5e00e35db..1ba159a8e6 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -55,7 +55,7 @@ PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f); PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f); -PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 100.0f); +PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f); PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0); PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing From d70d84c9a7be7f629542f40255396f6755239963 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 10 Feb 2014 13:35:11 +0100 Subject: [PATCH 41/87] Fixed wrong VEHICLE_TYPE for multicopters. --- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 50d02d9e47..52584677b6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -1,6 +1,6 @@ #!nsh -set VEHICLE_TYPE fw +set VEHICLE_TYPE mc if [ $DO_AUTOCONFIG == yes ] then From aea135a9ced3f1c7e1c4e3be0e5f0e310f96c82d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Feb 2014 13:41:40 +0100 Subject: [PATCH 42/87] fw_pos_control: flare altitude back to 15m --- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index a0447d90d2..512ca7b8ac 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -171,6 +171,6 @@ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); -PARAM_DEFINE_FLOAT(FW_LND_FLALT, 10.0f); +PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f); PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f); PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); From 36d1ec80ef264beb34604b3e2b9bb076fd78d52f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Feb 2014 15:12:32 +0100 Subject: [PATCH 43/87] Startup: don't configure anything if definitions are missing --- ROMFS/px4fmu_common/init.d/rcS | 28 ++++++++++++++++++---------- 1 file changed, 18 insertions(+), 10 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 178bcaeba5..ede835ab71 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -464,16 +464,20 @@ then if [ $MIXER == none ] then - # Set default mixer for multicopter if not defined - set MIXER quad_x + echo "Default mixer for multicopter not defined" fi if [ $MAV_TYPE == none ] then - # Use MAV_TYPE = 2 (quadcopter) if not defined - set MAV_TYPE 2 - # Use mixer to detect vehicle type + if [ $MIXER == FMU_quad_x -o $MIXER == FMU_quad_+ ] + then + set MAV_TYPE 2 + fi + if [ $MIXER == FMU_quad_w ] + then + set MAV_TYPE 2 + fi if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ] then set MAV_TYPE 13 @@ -487,8 +491,14 @@ then set MAV_TYPE 14 fi fi - - param set MAV_TYPE $MAV_TYPE + + # Still no MAV_TYPE found + if [ $MAV_TYPE == none ] + then + echo "Unknown MAV_TYPE" + else + param set MAV_TYPE $MAV_TYPE + fi # Load mixer and configure outputs sh /etc/init.d/rc.interface @@ -502,10 +512,8 @@ then # if [ $VEHICLE_TYPE == none ] then - echo "[init] Vehicle type: GENERIC" + echo "[init] Vehicle type: No autostart ID found" - # Load mixer and configure outputs - sh /etc/init.d/rc.interface fi # Start any custom addons From 0388d9adefb33c98f1e4350e3f2ed59a7fdd5359 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 11 Feb 2014 08:09:51 +0100 Subject: [PATCH 44/87] Hotfix and cleanup for system mixers --- ROMFS/px4fmu_common/init.d/11001_hexa_cox | 39 +++++ .../{12001_octo_cox_pwm => 12001_octo_cox} | 4 +- ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm | 2 +- ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm | 2 +- ROMFS/px4fmu_common/init.d/8001_octo_x_pwm | 2 +- ROMFS/px4fmu_common/init.d/9001_octo_+_pwm | 2 +- ROMFS/px4fmu_common/init.d/rc.autostart | 11 +- ROMFS/px4fmu_common/init.d/rcS | 12 +- ROMFS/px4fmu_common/mixers/FMU_hex_+.mix | 17 +- ROMFS/px4fmu_common/mixers/FMU_hex_x.mix | 17 +- ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix | 6 +- ROMFS/px4fmu_common/mixers/FMU_octo_x.mix | 6 +- ROMFS/px4fmu_common/mixers/README | 154 ------------------ ROMFS/px4fmu_common/mixers/hexa_cox.mix | 3 + 14 files changed, 70 insertions(+), 207 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/11001_hexa_cox rename ROMFS/px4fmu_common/init.d/{12001_octo_cox_pwm => 12001_octo_cox} (90%) delete mode 100644 ROMFS/px4fmu_common/mixers/README create mode 100644 ROMFS/px4fmu_common/mixers/hexa_cox.mix diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox new file mode 100644 index 0000000000..2dc83a517c --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox @@ -0,0 +1,39 @@ +#!nsh +# +# UNTESTED UNTESTED! +# +# Generic 10†Hexa coaxial geometry +# +# Lorenz Meier +# + +if [ $DO_AUTOCONFIG == yes ] +then + # + # Default parameters for this platform + # + param set MC_ATT_P 7.0 + param set MC_ATT_I 0.0 + param set MC_ATT_D 0.0 + param set MC_ATTRATE_P 0.12 + param set MC_ATTRATE_I 0.0 + param set MC_ATTRATE_D 0.004 + param set MC_YAWPOS_P 2.0 + param set MC_YAWPOS_I 0.0 + param set MC_YAWPOS_D 0.0 + param set MC_YAWRATE_P 0.3 + param set MC_YAWRATE_I 0.2 + param set MC_YAWRATE_D 0.005 + + # TODO add default MPC parameters +fi + +set VEHICLE_TYPE mc +set MIXER hexa_cox + +set PWM_OUTPUTS 12345678 +set PWM_RATE 400 +# DJI ESC range +set PWM_DISARMED 900 +set PWM_MIN 1200 +set PWM_MAX 1900 diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox_pwm b/ROMFS/px4fmu_common/init.d/12001_octo_cox similarity index 90% rename from ROMFS/px4fmu_common/init.d/12001_octo_cox_pwm rename to ROMFS/px4fmu_common/init.d/12001_octo_cox index 5f3cec4e0a..a55fc5a30d 100644 --- a/ROMFS/px4fmu_common/init.d/12001_octo_cox_pwm +++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox @@ -2,7 +2,7 @@ # # Generic 10†Octo coaxial geometry # -# Maintainers: Lorenz Meier +# Lorenz Meier # if [ $DO_AUTOCONFIG == yes ] @@ -29,7 +29,7 @@ fi set VEHICLE_TYPE mc set MIXER FMU_octo_cox -set PWM_OUTPUTS 1234 +set PWM_OUTPUTS 12345678 set PWM_RATE 400 # DJI ESC range set PWM_DISARMED 900 diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm b/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm index ddec8f36ef..4477967091 100644 --- a/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm +++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x_pwm @@ -29,7 +29,7 @@ fi set VEHICLE_TYPE mc set MIXER FMU_hexa_x -set PWM_OUTPUTS 1234 +set PWM_OUTPUTS 12345678 set PWM_RATE 400 # DJI ESC range set PWM_DISARMED 900 diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm b/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm index 106e0fb54c..c4e9560d17 100644 --- a/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm +++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+_pwm @@ -29,7 +29,7 @@ fi set VEHICLE_TYPE mc set MIXER FMU_hexa_+ -set PWM_OUTPUTS 1234 +set PWM_OUTPUTS 12345678 set PWM_RATE 400 # DJI ESC range set PWM_DISARMED 900 diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm b/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm index f0eea339b8..ea56195d4b 100644 --- a/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm +++ b/ROMFS/px4fmu_common/init.d/8001_octo_x_pwm @@ -29,7 +29,7 @@ fi set VEHICLE_TYPE mc set MIXER FMU_octo_x -set PWM_OUTPUTS 1234 +set PWM_OUTPUTS 12345678 set PWM_RATE 400 # DJI ESC range set PWM_DISARMED 900 diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm b/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm index 992a7aeba6..f7693875c5 100644 --- a/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm +++ b/ROMFS/px4fmu_common/init.d/9001_octo_+_pwm @@ -29,7 +29,7 @@ fi set VEHICLE_TYPE mc set MIXER FMU_octo_+ -set PWM_OUTPUTS 1234 +set PWM_OUTPUTS 12345678 set PWM_RATE 400 # DJI ESC range set PWM_DISARMED 900 diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 00baed6468..38b1cb57e6 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -185,11 +185,20 @@ then sh /etc/init.d/10016_3dr_iris fi +# +# Hexa Coaxial +# + +if param compare SYS_AUTOSTART 11001 +then + sh /etc/init.d/11001_hexa_cox +fi + # # Octo Coaxial # if param compare SYS_AUTOSTART 12001 then - sh /etc/init.d/12001_octo_cox_pwm + sh /etc/init.d/12001_octo_cox fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 6f4e1f3b56..50ac9759a5 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -467,19 +467,23 @@ then # Use mixer to detect vehicle type if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ] then - param set MAV_TYPE 13 + set MAV_TYPE 13 + fi + if [ $MIXER == hexa_cox ] + then + set MAV_TYPE 13 fi if [ $MIXER == FMU_octo_x -o $MIXER == FMU_octo_+ ] then - param set MAV_TYPE 14 + set MAV_TYPE 14 fi if [ $MIXER == FMU_octo_cox ] then - param set MAV_TYPE 14 + set MAV_TYPE 14 fi fi - param set MAV_TYPE $MAV_TYPE + param set MAV_TYPE $MAV_TYPE # Load mixer and configure outputs sh /etc/init.d/rc.interface diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix index f8f9f0e4dc..e608b459f8 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix @@ -1,18 +1,3 @@ -Multirotor mixer for PX4FMU -=========================== - -This file defines a single mixer for a hexacopter in the + configuration. All controls -are mixed 100%. +# Hexa + R: 6+ 10000 10000 10000 0 - -Gimbal / payload mixer for last two channels ------------------------------------------------------ - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 6 10000 10000 0 -10000 10000 - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 7 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix index 26b40b9e95..16e6e22f90 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix @@ -1,18 +1,3 @@ -Multirotor mixer for PX4FMU -=========================== - -This file defines a single mixer for a hexacopter in the X configuration. All controls -are mixed 100%. +# Hexa X R: 6x 10000 10000 10000 0 - -Gimbal / payload mixer for last two channels ------------------------------------------------------ - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 6 10000 10000 0 -10000 10000 - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 7 10000 10000 0 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix index 51cebb7858..f7845450d3 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_octo_cox.mix @@ -1,7 +1,3 @@ -Multirotor mixer for PX4FMU -=========================== - -This file defines a single mixer for a Coaxial Octocopter in the X configuration. All controls -are mixed 100%. +# Octo coaxial R: 8c 10000 10000 10000 0 diff --git a/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix b/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix index edc71f0139..c9a348aa42 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_octo_x.mix @@ -1,7 +1,3 @@ -Multirotor mixer for PX4FMU -=========================== - -This file defines a single mixer for a octocopter in the X configuration. All controls -are mixed 100%. +# Octo X R: 8x 10000 10000 10000 0 diff --git a/ROMFS/px4fmu_common/mixers/README b/ROMFS/px4fmu_common/mixers/README deleted file mode 100644 index 6649c53c20..0000000000 --- a/ROMFS/px4fmu_common/mixers/README +++ /dev/null @@ -1,154 +0,0 @@ -PX4 mixer definitions -===================== - -Files in this directory implement example mixers that can be used as a basis -for customisation, or for general testing purposes. - -Mixer basics ------------- - -Mixers combine control values from various sources (control tasks, user inputs, -etc.) and produce output values suitable for controlling actuators; servos, -motors, switches and so on. - -An actuator derives its value from the combination of one or more control -values. Each of the control values is scaled according to the actuator's -configuration and then combined to produce the actuator value, which may then be -further scaled to suit the specific output type. - -Internally, all scaling is performed using floating point values. Inputs and -outputs are clamped to the range -1.0 to 1.0. - -control control control - | | | - v v v - scale scale scale - | | | - | v | - +-------> mix <------+ - | - scale - | - v - out - -Scaling -------- - -Basic scalers provide linear scaling of the input to the output. - -Each scaler allows the input value to be scaled independently for inputs -greater/less than zero. An offset can be applied to the output, and lower and -upper boundary constraints can be applied. Negative scaling factors cause the -output to be inverted (negative input produces positive output). - -Scaler pseudocode: - -if (input < 0) - output = (input * NEGATIVE_SCALE) + OFFSET -else - output = (input * POSITIVE_SCALE) + OFFSET - -if (output < LOWER_LIMIT) - output = LOWER_LIMIT -if (output > UPPER_LIMIT) - output = UPPER_LIMIT - -Syntax ------- - -Mixer definitions are text files; lines beginning with a single capital letter -followed by a colon are significant. All other lines are ignored, meaning that -explanatory text can be freely mixed with the definitions. - -Each file may define more than one mixer; the allocation of mixers to actuators -is specific to the device reading the mixer definition, and the number of -actuator outputs generated by a mixer is specific to the mixer. - -A mixer begins with a line of the form - - : - -The tag selects the mixer type; 'M' for a simple summing mixer, 'R' for a -multirotor mixer, etc. - -Null Mixer -.......... - -A null mixer consumes no controls and generates a single actuator output whose -value is always zero. Typically a null mixer is used as a placeholder in a -collection of mixers in order to achieve a specific pattern of actuator outputs. - -The null mixer definition has the form: - - Z: - -Simple Mixer -............ - -A simple mixer combines zero or more control inputs into a single actuator -output. Inputs are scaled, and the mixing function sums the result before -applying an output scaler. - -A simple mixer definition begins with: - - M: - O: <-ve scale> <+ve scale> - -If is zero, the sum is effectively zero and the mixer will -output a fixed value that is constrained by and . - -The second line defines the output scaler with scaler parameters as discussed -above. Whilst the calculations are performed as floating-point operations, the -values stored in the definition file are scaled by a factor of 10000; i.e. an -offset of -0.5 is encoded as -5000. - -The definition continues with entries describing the control -inputs and their scaling, in the form: - - S: <-ve scale> <+ve scale> - -The value identifies the control group from which the scaler will read, -and the value an offset within that group. These values are specific to -the device reading the mixer definition. - -When used to mix vehicle controls, mixer group zero is the vehicle attitude -control group, and index values zero through three are normally roll, pitch, -yaw and thrust respectively. - -The remaining fields on the line configure the control scaler with parameters as -discussed above. Whilst the calculations are performed as floating-point -operations, the values stored in the definition file are scaled by a factor of -10000; i.e. an offset of -0.5 is encoded as -5000. - -Multirotor Mixer -................ - -The multirotor mixer combines four control inputs (roll, pitch, yaw, thrust) -into a set of actuator outputs intended to drive motor speed controllers. - -The mixer definition is a single line of the form: - -R: - -The supported geometries include: - - 4x - quadrotor in X configuration - 4+ - quadrotor in + configuration - 6x - hexcopter in X configuration - 6+ - hexcopter in + configuration - 8x - octocopter in X configuration - 8+ - octocopter in + configuration - -Each of the roll, pitch and yaw scale values determine scaling of the roll, -pitch and yaw controls relative to the thrust control. Whilst the calculations -are performed as floating-point operations, the values stored in the definition -file are scaled by a factor of 10000; i.e. an factor of 0.5 is encoded as 5000. - -Roll, pitch and yaw inputs are expected to range from -1.0 to 1.0, whilst the -thrust input ranges from 0.0 to 1.0. Output for each actuator is in the -range -1.0 to 1.0. - -In the case where an actuator saturates, all actuator values are rescaled so that -the saturating actuator is limited to 1.0. diff --git a/ROMFS/px4fmu_common/mixers/hexa_cox.mix b/ROMFS/px4fmu_common/mixers/hexa_cox.mix new file mode 100644 index 0000000000..497786feb5 --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/hexa_cox.mix @@ -0,0 +1,3 @@ +# Hexa coaxial + +R: 6c 10000 10000 10000 0 From 3c592e3a06aa6a0357b9540d8cc1f68333b1c256 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Feb 2014 15:35:26 +0100 Subject: [PATCH 45/87] Startup: fix merge mistake --- ROMFS/px4fmu_common/init.d/rcS | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 588a44a013..76f021e339 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -479,6 +479,7 @@ then set MAV_TYPE 2 fi if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ] + then set MAV_TYPE 13 fi if [ $MIXER == hexa_cox ] From 16908f9aff0e7ad0f967613adf2be9a00c1c6cce Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 11 Feb 2014 23:24:49 +0100 Subject: [PATCH 46/87] autostart for multicopters: frame-specific default parameters reverted and cleaned up --- .../px4fmu_common/init.d/10015_tbs_discovery | 21 ++++++++++++-- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 17 +++++++++-- ROMFS/px4fmu_common/init.d/11001_hexa_cox | 28 ++---------------- ROMFS/px4fmu_common/init.d/12001_octo_cox | 29 ++----------------- ROMFS/px4fmu_common/init.d/4001_quad_x | 2 +- ROMFS/px4fmu_common/init.d/4010_dji_f330 | 19 +++++++++++- ROMFS/px4fmu_common/init.d/4011_dji_f450 | 20 ++++++++++++- ROMFS/px4fmu_common/init.d/4012_hk_x550 | 8 ----- ROMFS/px4fmu_common/init.d/5001_quad_+ | 2 +- ROMFS/px4fmu_common/init.d/6001_hexa_x | 5 ++-- ROMFS/px4fmu_common/init.d/7001_hexa_+ | 5 ++-- ROMFS/px4fmu_common/init.d/8001_octo_x | 2 +- ROMFS/px4fmu_common/init.d/rc.autostart | 5 ---- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 24 +++++++-------- 14 files changed, 92 insertions(+), 95 deletions(-) delete mode 100644 ROMFS/px4fmu_common/init.d/4012_hk_x550 diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index b09765e8e7..880e4899b1 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -2,11 +2,28 @@ # # Team Blacksheep Discovery Quadcopter # -# Simon Wilks +# Anton Babushkin , Simon Wilks # sh /etc/init.d/rc.mc_defaults +if [ $DO_AUTOCONFIG == yes ] +then + # TODO review MC_YAWRATE_I + param set MC_ROLL_P 8.0 + param set MC_ROLLRATE_P 0.07 + param set MC_ROLLRATE_I 0.05 + param set MC_ROLLRATE_D 0.0017 + param set MC_PITCH_P 8.0 + param set MC_PITCHRATE_P 0.14 + param set MC_PITCHRATE_I 0.1 + param set MC_PITCHRATE_D 0.0025 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.28 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 +fi + set MIXER FMU_quad_w -set PWM_OUTPUTS 1234 \ No newline at end of file +set PWM_OUTPUTS 1234 diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 42d5169935..d691a6f2e6 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -9,9 +9,20 @@ sh /etc/init.d/rc.mc_defaults if [ $DO_AUTOCONFIG == yes ] then - # - # Default parameters for this platform - # + # TODO tune roll/pitch separately + param set MC_ROLL_P 9.0 + param set MC_ROLLRATE_P 0.13 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.004 + param set MC_PITCH_P 9.0 + param set MC_PITCHRATE_P 0.13 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.004 + param set MC_YAW_P 0.5 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 + param set BAT_V_SCALING 0.00989 param set BAT_C_SCALING 0.0124 fi diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox index 2dc83a517c..b98ab47748 100644 --- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox +++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox @@ -7,33 +7,9 @@ # Lorenz Meier # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ATT_P 7.0 - param set MC_ATT_I 0.0 - param set MC_ATT_D 0.0 - param set MC_ATTRATE_P 0.12 - param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_D 0.004 - param set MC_YAWPOS_P 2.0 - param set MC_YAWPOS_I 0.0 - param set MC_YAWPOS_D 0.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - - # TODO add default MPC parameters -fi +sh /etc/init.d/rc.mc_defaults -set VEHICLE_TYPE mc set MIXER hexa_cox +# We only can run one channel group with one rate, so set all 8 channels set PWM_OUTPUTS 12345678 -set PWM_RATE 400 -# DJI ESC range -set PWM_DISARMED 900 -set PWM_MIN 1200 -set PWM_MAX 1900 diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox index a55fc5a30d..655cb6226e 100644 --- a/ROMFS/px4fmu_common/init.d/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox @@ -5,33 +5,8 @@ # Lorenz Meier # -if [ $DO_AUTOCONFIG == yes ] -then - # - # Default parameters for this platform - # - param set MC_ATT_P 7.0 - param set MC_ATT_I 0.0 - param set MC_ATT_D 0.0 - param set MC_ATTRATE_P 0.12 - param set MC_ATTRATE_I 0.0 - param set MC_ATTRATE_D 0.004 - param set MC_YAWPOS_P 2.0 - param set MC_YAWPOS_I 0.0 - param set MC_YAWPOS_D 0.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - - # TODO add default MPC parameters -fi +sh /etc/init.d/rc.mc_defaults -set VEHICLE_TYPE mc -set MIXER FMU_octo_cox +set MIXER octo_cox set PWM_OUTPUTS 12345678 -set PWM_RATE 400 -# DJI ESC range -set PWM_DISARMED 900 -set PWM_MIN 1200 -set PWM_MAX 1900 diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x index fa751f1e31..345b0e3e4e 100644 --- a/ROMFS/px4fmu_common/init.d/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/4001_quad_x @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_x -set PWM_OUTPUTS 1234 \ No newline at end of file +set PWM_OUTPUTS 1234 diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 232af57b4a..cd4480c3eb 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -7,4 +7,21 @@ sh /etc/init.d/4001_quad_x -set PWM_MIN 1175 \ No newline at end of file +if [ $DO_AUTOCONFIG == yes ] +then + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.1 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.003 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.1 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.003 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 +fi + +set PWM_MIN 1175 +set PWM_MAX 1900 diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 259636acc2..ac2ecc70aa 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -7,4 +7,22 @@ sh /etc/init.d/4001_quad_x -set PWM_MIN 1175 \ No newline at end of file +if [ $DO_AUTOCONFIG == yes ] +then + # TODO REVIEW + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.1 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.003 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.1 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.003 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 +fi + +set PWM_MIN 1175 +set PWM_MAX 1900 diff --git a/ROMFS/px4fmu_common/init.d/4012_hk_x550 b/ROMFS/px4fmu_common/init.d/4012_hk_x550 deleted file mode 100644 index a5c4a86902..0000000000 --- a/ROMFS/px4fmu_common/init.d/4012_hk_x550 +++ /dev/null @@ -1,8 +0,0 @@ -#!nsh -# -# HobbyKing X550 Quadcopter -# -# Todd Stellanova -# - -sh /etc/init.d/4001_quad_x diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+ index 2f5ab44d77..55b31067d1 100644 --- a/ROMFS/px4fmu_common/init.d/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/5001_quad_+ @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_quad_+ -set PWM_OUTPUTS 1234 \ No newline at end of file +set PWM_OUTPUTS 1234 diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x index 73ef12569b..7714a508cf 100644 --- a/ROMFS/px4fmu_common/init.d/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x @@ -9,6 +9,5 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_x -# We only can run one channel group with one rate, -# so all 8 at 400 Hz -set PWM_OUTPUTS 12345678 \ No newline at end of file +# We only can run one channel group with one rate, so set all 8 channels +set PWM_OUTPUTS 12345678 diff --git a/ROMFS/px4fmu_common/init.d/7001_hexa_+ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ index ef4b6297de..60db8c0690 100644 --- a/ROMFS/px4fmu_common/init.d/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ @@ -9,6 +9,5 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_+ -# We only can run one channel group with one rate, -# so all 8 at 400 Hz -set PWM_OUTPUTS 12345678 \ No newline at end of file +# We only can run one channel group with one rate, so set all 8 channels +set PWM_OUTPUTS 12345678 diff --git a/ROMFS/px4fmu_common/init.d/8001_octo_x b/ROMFS/px4fmu_common/init.d/8001_octo_x index bb87f89fe7..411aee1140 100644 --- a/ROMFS/px4fmu_common/init.d/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/8001_octo_x @@ -9,4 +9,4 @@ sh /etc/init.d/rc.mc_defaults set MIXER FMU_octo_x -set PWM_OUTPUTS 12345678 \ No newline at end of file +set PWM_OUTPUTS 12345678 diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 48c26aacd1..3968af58ea 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -116,11 +116,6 @@ then sh /etc/init.d/4011_dji_f450 fi -if param compare SYS_AUTOSTART 4012 12 -then - sh /etc/init.d/4012_hk_x550 -fi - # # Quad + # diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 52584677b6..4db62607a9 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -4,22 +4,20 @@ set VEHICLE_TYPE mc if [ $DO_AUTOCONFIG == yes ] then - # - # Default parameters for MC - # param set MC_ROLL_P 7.0 - param set MC_ROLLRATE_P 0.12 + param set MC_ROLLRATE_P 0.1 param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.004 + param set MC_ROLLRATE_D 0.003 param set MC_PITCH_P 7.0 - param set MC_PITCHRATE_P 0.12 + param set MC_PITCHRATE_P 0.1 param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 2.0 - param set MC_YAWRATE_P 0.3 - param set MC_YAWRATE_I 0.2 - param set MC_YAWRATE_D 0.005 - + param set MC_PITCHRATE_D 0.003 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 + param set MC_YAW_FF 0.5 + param set MPC_THR_MAX 1.0 param set MPC_THR_MIN 0.1 param set MPC_XY_P 1.0 @@ -42,4 +40,4 @@ fi set PWM_RATE 400 set PWM_DISARMED 900 set PWM_MIN 1075 -set PWM_MAX 2000 \ No newline at end of file +set PWM_MAX 2000 From 179aa17a3842bb68fa3849e890d20cfb9a1a5392 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 12 Feb 2014 12:21:23 +0100 Subject: [PATCH 47/87] sdlog2: TELE (telemetry status) message added, type for 'rssi' and 'remote_rssi' in 'telemetry_status' topic fixed to be consistent with 'noise'/'remote_noise' and mavlink message. --- src/modules/sdlog2/sdlog2.c | 24 ++++++++++++++++++++++ src/modules/sdlog2/sdlog2_messages.h | 14 +++++++++++++ src/modules/uORB/topics/telemetry_status.h | 10 ++++----- 3 files changed, 43 insertions(+), 5 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 3c218e21fb..68e6a7469f 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -82,6 +82,7 @@ #include #include #include +#include #include #include @@ -758,6 +759,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct esc_status_s esc; struct vehicle_global_velocity_setpoint_s global_vel_sp; struct battery_status_s battery; + struct telemetry_status_s telemetry; } buf; memset(&buf, 0, sizeof(buf)); @@ -783,6 +785,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int esc_sub; int global_vel_sp_sub; int battery_sub; + int telemetry_sub; } subs; /* log message buffer: header + body */ @@ -811,6 +814,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_GVSP_s log_GVSP; struct log_BATT_s log_BATT; struct log_DIST_s log_DIST; + struct log_TELE_s log_TELE; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -946,6 +950,12 @@ int sdlog2_thread_main(int argc, char *argv[]) fds[fdsc_count].events = POLLIN; fdsc_count++; + /* --- TELEMETRY STATUS --- */ + subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status)); + fds[fdsc_count].fd = subs.telemetry_sub; + fds[fdsc_count].events = POLLIN; + fdsc_count++; + /* WARNING: If you get the error message below, * then the number of registered messages (fdsc) * differs from the number of messages in the above list. @@ -1347,6 +1357,20 @@ int sdlog2_thread_main(int argc, char *argv[]) LOGBUFFER_WRITE_AND_COUNT(BATT); } + /* --- TELEMETRY --- */ + if (fds[ifds++].revents & POLLIN) { + orb_copy(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry); + log_msg.msg_type = LOG_TELE_MSG; + log_msg.body.log_TELE.rssi = buf.telemetry.rssi; + log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi; + log_msg.body.log_TELE.noise = buf.telemetry.noise; + log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise; + log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors; + log_msg.body.log_TELE.fixed = buf.telemetry.fixed; + log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf; + LOGBUFFER_WRITE_AND_COUNT(TELE); + } + /* signal the other thread new data, but not yet unlock */ if (logbuffer_count(&lb) > MIN_BYTES_TO_WRITE) { /* only request write if several packets can be written at once */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index db87e3a6a2..16bfc355d6 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -264,6 +264,18 @@ struct log_DIST_s { uint8_t flags; }; +/* --- TELE - TELEMETRY STATUS --- */ +#define LOG_TELE_MSG 22 +struct log_TELE_s { + uint8_t rssi; + uint8_t remote_rssi; + uint8_t noise; + uint8_t remote_noise; + uint16_t rxerrors; + uint16_t fixed; + uint8_t txbuf; +}; + /********** SYSTEM MESSAGES, ID > 0x80 **********/ /* --- TIME - TIME STAMP --- */ @@ -311,6 +323,8 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"), LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"), LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"), + LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"), + /* system-level messages, ID >= 0x80 */ // FMT: don't write format of format message, it's useless LOG_FORMAT(TIME, "Q", "StartTime"), diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index 828fb31cc7..5192d4d589 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -58,10 +58,10 @@ enum TELEMETRY_STATUS_RADIO_TYPE { struct telemetry_status_s { uint64_t timestamp; enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */ - unsigned rssi; /**< local signal strength */ - unsigned remote_rssi; /**< remote signal strength */ - unsigned rxerrors; /**< receive errors */ - unsigned fixed; /**< count of error corrected packets */ + uint8_t rssi; /**< local signal strength */ + uint8_t remote_rssi; /**< remote signal strength */ + uint16_t rxerrors; /**< receive errors */ + uint16_t fixed; /**< count of error corrected packets */ uint8_t noise; /**< background noise level */ uint8_t remote_noise; /**< remote background noise level */ uint8_t txbuf; /**< how full the tx buffer is as a percentage */ @@ -73,4 +73,4 @@ struct telemetry_status_s { ORB_DECLARE(telemetry_status); -#endif /* TOPIC_TELEMETRY_STATUS_H */ \ No newline at end of file +#endif /* TOPIC_TELEMETRY_STATUS_H */ From 3d83c45f7585c71bee3f07ea414d798ab7e2bae5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 12 Feb 2014 13:20:15 +0100 Subject: [PATCH 48/87] mavlink: bug in telemetry_status publication fixed --- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index a371a499ef..1dbe564955 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -351,7 +351,7 @@ handle_message(mavlink_message_t *msg) tstatus.rxerrors = rstatus.rxerrors; tstatus.fixed = rstatus.fixed; - if (telemetry_status_pub == 0) { + if (telemetry_status_pub <= 0) { telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus); } else { From f6694c2cef62ee3284598ed1b4d8c6954effab4e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 13 Feb 2014 00:03:51 +0100 Subject: [PATCH 49/87] rc.fw_defaults: increase acceptance radius which is used by navigator to generate virtual waypoints (RTL etc.) --- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 3e340699fc..3a50fcf56f 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -10,4 +10,5 @@ then param set NAV_LAND_ALT 90 param set NAV_RTL_ALT 100 param set NAV_RTL_LAND_T -1 + param set NAV_ACCEPT_RAD 50 fi \ No newline at end of file From 4982e819837195aa512fb977639ce1dd0c0cec3a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 13 Feb 2014 15:30:06 +0100 Subject: [PATCH 50/87] Navigator: set loiter WP correctly --- src/modules/navigator/navigator_main.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 5139ae6cd2..260356eca9 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1080,9 +1080,8 @@ Navigator::start_loiter() mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude"); } - _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER; } - + _pos_sp_triplet.current.type = SETPOINT_TYPE_LOITER; _pos_sp_triplet.current.loiter_radius = _parameters.loiter_radius; _pos_sp_triplet.current.loiter_direction = 1; _pos_sp_triplet.previous.valid = false; From 036ebdbe78defdcc8c1cf5955e8df773a16e7e8c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 13 Feb 2014 16:08:49 +0100 Subject: [PATCH 51/87] Commander: add guard for parachute deployment --- src/modules/commander/commander.cpp | 14 +++++++++----- src/modules/navigator/navigator_params.c | 1 + 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index c039b85737..8129dddb30 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -152,6 +152,7 @@ static uint64_t last_print_mode_reject_time = 0; static bool on_usb_power = false; static float takeoff_alt = 5.0f; +static int parachute_enabled = 0; static struct vehicle_status_s status; static struct actuator_armed_s armed; @@ -563,7 +564,9 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe /* Flight termination */ case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command - if (armed->armed && cmd->param3 > 0.5) { //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO + //XXX: to enable the parachute, a param needs to be set + //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO + if (armed->armed && cmd->param3 > 0.5 && parachute_enabled) { transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION); result = VEHICLE_CMD_RESULT_ACCEPTED; ret = true; @@ -615,6 +618,7 @@ int commander_thread_main(int argc, char *argv[]) param_t _param_system_id = param_find("MAV_SYS_ID"); param_t _param_component_id = param_find("MAV_COMP_ID"); param_t _param_takeoff_alt = param_find("NAV_TAKEOFF_ALT"); + param_t _param_enable_parachute = param_find("NAV_PARACHUTE_EN"); /* welcome user */ warnx("starting"); @@ -860,10 +864,10 @@ int commander_thread_main(int argc, char *argv[]) /* re-check RC calibration */ rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd)); - - /* navigation parameters */ - param_get(_param_takeoff_alt, &takeoff_alt); } + /* navigation parameters */ + param_get(_param_takeoff_alt, &takeoff_alt); + param_get(_param_enable_parachute, ¶chute_enabled); } orb_check(sp_man_sub, &updated); @@ -1251,7 +1255,7 @@ int commander_thread_main(int argc, char *argv[]) // TODO remove this hack /* flight termination in manual mode if assisted switch is on easy position */ - if (!status.is_rotary_wing && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch > STICK_ON_OFF_LIMIT) { + if (!status.is_rotary_wing && parachute_enabled && armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch > STICK_ON_OFF_LIMIT) { if (TRANSITION_CHANGED == failsafe_state_transition(&status, FAILSAFE_STATE_TERMINATION)) { tune_positive(); } diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 1ba159a8e6..9e05bbffa8 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -61,3 +61,4 @@ PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); // delay after descend before landing, if set to -1 the system will not land but loiter at NAV_LAND_ALT +PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0); // enable parachute deployment From 08f1e6a9dc86c03015cb2a83dc94c3412d6d9eb4 Mon Sep 17 00:00:00 2001 From: px4dev Date: Thu, 13 Feb 2014 09:20:33 -0800 Subject: [PATCH 52/87] Fix base clock frequencies for timers 9/10/11 (not currently used). Thanks to xiazibin@gmail.com for pointing these out. --- nuttx-configs/px4fmu-v2/include/board.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h index 850043ddf5..3bede8a1f7 100755 --- a/nuttx-configs/px4fmu-v2/include/board.h +++ b/nuttx-configs/px4fmu-v2/include/board.h @@ -141,9 +141,9 @@ #define STM32_APB2_TIM1_CLKIN (2*STM32_PCLK2_FREQUENCY) #define STM32_APB2_TIM8_CLKIN (2*STM32_PCLK2_FREQUENCY) -#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK1_FREQUENCY) -#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK1_FREQUENCY) +#define STM32_APB2_TIM9_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM10_CLKIN (2*STM32_PCLK2_FREQUENCY) +#define STM32_APB2_TIM11_CLKIN (2*STM32_PCLK2_FREQUENCY) /* Timer Frequencies, if APBx is set to 1, frequency is same to APBx * otherwise frequency is 2xAPBx. From ccfe476326d8b01e33a3a7ea115054a31fa7a2b9 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 13 Feb 2014 20:53:47 +0100 Subject: [PATCH 53/87] decrease MC_PITCHRATE_P for TBS Discovery --- ROMFS/px4fmu_common/init.d/10015_tbs_discovery | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index 880e4899b1..fe85f7d35d 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -2,7 +2,7 @@ # # Team Blacksheep Discovery Quadcopter # -# Anton Babushkin , Simon Wilks +# Anton Babushkin , Simon Wilks , Thomas Gubler # sh /etc/init.d/rc.mc_defaults @@ -15,7 +15,7 @@ then param set MC_ROLLRATE_I 0.05 param set MC_ROLLRATE_D 0.0017 param set MC_PITCH_P 8.0 - param set MC_PITCHRATE_P 0.14 + param set MC_PITCHRATE_P 0.1 param set MC_PITCHRATE_I 0.1 param set MC_PITCHRATE_D 0.0025 param set MC_YAW_P 2.8 From 7441efde4745c0dddc08a36a0bbf83307f82948a Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Fri, 14 Feb 2014 01:48:00 +0100 Subject: [PATCH 54/87] Add a lot of MAVLink parameter documentation. --- .../launchdetection/launchdetection_params.c | 48 ++- src/modules/commander/commander_params.c | 32 ++ src/modules/mavlink/mavlink.c | 12 + src/modules/navigator/geofence_params.c | 16 +- src/modules/navigator/navigator_params.c | 63 +++- src/modules/sensors/sensor_params.c | 303 ++++++++++++++++-- src/modules/systemlib/system_params.c | 19 +- 7 files changed, 433 insertions(+), 60 deletions(-) diff --git a/src/lib/launchdetection/launchdetection_params.c b/src/lib/launchdetection/launchdetection_params.c index 63a8981aa8..45d7957f11 100644 --- a/src/lib/launchdetection/launchdetection_params.c +++ b/src/lib/launchdetection/launchdetection_params.c @@ -45,28 +45,46 @@ #include /* - * Launch detection parameters, accessible via MAVLink + * Catapult launch detection parameters, accessible via MAVLink * */ -/* Catapult Launch detection */ - -// @DisplayName Switch to enable launchdetection -// @Description if set to 1 launchdetection is enabled -// @Range 0 or 1 +/** + * Enable launch detection. + * + * @min 0 + * @max 1 + * @group Launch detection + */ PARAM_DEFINE_INT32(LAUN_ALL_ON, 0); -// @DisplayName Catapult Accelerometer Threshold -// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection -// @Range > 0 +/** + * Catapult accelerometer theshold. + * + * LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection. + * + * @min 0 + * @group Launch detection + */ PARAM_DEFINE_FLOAT(LAUN_CAT_A, 30.0f); -// @DisplayName Catapult Time Threshold -// @Description LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection -// @Range > 0, in seconds +/** + * Catapult time theshold. + * + * LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection. + * + * @min 0 + * @group Launch detection + */ PARAM_DEFINE_FLOAT(LAUN_CAT_T, 0.05f); -// @DisplayName Throttle setting while detecting the launch -// @Description The throttle is set to this value while the system is waiting for the takeoff -// @Range 0 to 1 +/** + * Throttle setting while detecting launch. + * + * The throttle is set to this value while the system is waiting for the take-off. + * + * @min 0 + * @max 1 + * @group Launch detection + */ PARAM_DEFINE_FLOAT(LAUN_THR_PRE, 0.0f); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index d3155f7bf5..80ca68f21f 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -48,7 +48,39 @@ PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f); PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f); PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f); + +/** + * Empty cell voltage. + * + * Defines the voltage where a single cell of the battery is considered empty. + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); + +/** + * Full cell voltage. + * + * Defines the voltage where a single cell of the battery is considered full. + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f); + +/** + * Number of cells. + * + * Defines the number of cells the attached battery consists of. + * + * @group Battery Calibration + */ PARAM_DEFINE_INT32(BAT_N_CELLS, 3); + +/** + * Battery capacity. + * + * Defines the capacity of the attached battery. + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_CAPACITY, -1.0f); diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 4d975066f7..ade4469c58 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -76,8 +76,20 @@ #include /* define MAVLink specific parameters */ +/** + * MAVLink system ID + * @group MAVLink + */ PARAM_DEFINE_INT32(MAV_SYS_ID, 1); +/** + * MAVLink component ID + * @group MAVLink + */ PARAM_DEFINE_INT32(MAV_COMP_ID, 50); +/** + * MAVLink type + * @group MAVLink + */ PARAM_DEFINE_INT32(MAV_TYPE, MAV_TYPE_FIXED_WING); __EXPORT int mavlink_main(int argc, char *argv[]); diff --git a/src/modules/navigator/geofence_params.c b/src/modules/navigator/geofence_params.c index 20dd1fe2f0..5831a0ca94 100644 --- a/src/modules/navigator/geofence_params.c +++ b/src/modules/navigator/geofence_params.c @@ -45,11 +45,17 @@ #include /* - * geofence parameters, accessible via MAVLink - * + * Geofence parameters, accessible via MAVLink */ -// @DisplayName Switch to enable geofence -// @Description if set to 1 geofence is enabled, defaults to 1 because geofence is only enabled when the geofence.txt file is present -// @Range 0 or 1 +/** + * Enable geofence. + * + * Set to 1 to enable geofence. + * Defaults to 1 because geofence is only enabled when the geofence.txt file is present. + * + * @min 0 + * @max 1 + * @group Geofence + */ PARAM_DEFINE_INT32(GF_ON, 1); diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 9e05bbffa8..ec7a4e2296 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -50,15 +50,72 @@ /* * Navigator parameters, accessible via MAVLink - * */ +/** + * Minimum altitude + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f); + +/** + * Waypoint acceptance radius. + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f); + +/** + * Loiter radius. + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f); + +/** + * @group Navigation + */ PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0); + +/** + * Default take-off altitude. + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude + +/** + * Landing altitude. + * + * Slowly descend from this altitude when landing. + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing + +/** + * Return-to-land altitude. + * + * Minimum altitude for going home in RTL mode. + * + * @group Navigation + */ PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode -PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); // delay after descend before landing, if set to -1 the system will not land but loiter at NAV_LAND_ALT -PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0); // enable parachute deployment + +/** + * Return-to-land delay. + * + * Delay after descend before landing. + * If set to -1 the system will not land but loiter at NAV_LAND_ALT. + * + * @group Navigation + */ +PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); + +/** + * Enable parachute deployment. + * + * @group Navigation + */ +PARAM_DEFINE_INT32(NAV_PARACHUTE_EN, 0); diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 30659fd3a0..288c6e00a0 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -42,13 +42,10 @@ */ #include - #include /** - * Gyro X offset - * - * This is an X-axis offset for the gyro. Adjust it according to the calibration data. + * Gyro X-axis offset * * @min -10.0 * @max 10.0 @@ -57,7 +54,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f); /** - * Gyro Y offset + * Gyro Y-axis offset * * @min -10.0 * @max 10.0 @@ -66,7 +63,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XOFF, 0.0f); PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f); /** - * Gyro Z offset + * Gyro Z-axis offset * * @min -5.0 * @max 5.0 @@ -75,9 +72,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YOFF, 0.0f); PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f); /** - * Gyro X scaling - * - * X-axis scaling. + * Gyro X-axis scaling factor * * @min -1.5 * @max 1.5 @@ -86,9 +81,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZOFF, 0.0f); PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f); /** - * Gyro Y scaling - * - * Y-axis scaling. + * Gyro Y-axis scaling factor * * @min -1.5 * @max 1.5 @@ -97,9 +90,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_XSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f); /** - * Gyro Z scaling - * - * Z-axis scaling. + * Gyro Z-axis scaling factor * * @min -1.5 * @max 1.5 @@ -107,10 +98,9 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_YSCALE, 1.0f); */ PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f); + /** - * Magnetometer X offset - * - * This is an X-axis offset for the magnetometer. + * Magnetometer X-axis offset * * @min -500.0 * @max 500.0 @@ -119,9 +109,7 @@ PARAM_DEFINE_FLOAT(SENS_GYRO_ZSCALE, 1.0f); PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f); /** - * Magnetometer Y offset - * - * This is an Y-axis offset for the magnetometer. + * Magnetometer Y-axis offset * * @min -500.0 * @max 500.0 @@ -130,9 +118,7 @@ PARAM_DEFINE_FLOAT(SENS_MAG_XOFF, 0.0f); PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f); /** - * Magnetometer Z offset - * - * This is an Z-axis offset for the magnetometer. + * Magnetometer Z-axis offset * * @min -500.0 * @max 500.0 @@ -140,24 +126,134 @@ PARAM_DEFINE_FLOAT(SENS_MAG_YOFF, 0.0f); */ PARAM_DEFINE_FLOAT(SENS_MAG_ZOFF, 0.0f); +/** + * Magnetometer X-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_MAG_XSCALE, 1.0f); + +/** + * Magnetometer Y-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_MAG_YSCALE, 1.0f); + +/** + * Magnetometer Z-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_MAG_ZSCALE, 1.0f); + +/** + * Accelerometer X-axis offset + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_XOFF, 0.0f); + +/** + * Accelerometer Y-axis offset + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_YOFF, 0.0f); + +/** + * Accelerometer Z-axis offset + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_ZOFF, 0.0f); +/** + * Accelerometer X-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_XSCALE, 1.0f); + +/** + * Accelerometer Y-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_YSCALE, 1.0f); + +/** + * Accelerometer Z-axis scaling factor + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); + +/** + * Differential pressure sensor offset + * + * @group Sensor Calibration + */ PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f); + +/** + * Differential pressure sensor analog enabled + * + * @group Sensor Calibration + */ PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0); + +/** + * Board rotation + * + * This parameter defines the rotation of the FMU board relative to the platform. + * Possible values are: + * 0 = No rotation + * 1 = Yaw 45° + * 2 = Yaw 90° + * 3 = Yaw 135° + * 4 = Yaw 180° + * 5 = Yaw 225° + * 6 = Yaw 270° + * 7 = Yaw 315° + * 8 = Roll 180° + * 9 = Roll 180°, Yaw 45° + * 10 = Roll 180°, Yaw 90° + * 11 = Roll 180°, Yaw 135° + * 12 = Pitch 180° + * 13 = Roll 180°, Yaw 225° + * 14 = Roll 180°, Yaw 270° + * 15 = Roll 180°, Yaw 315° + * 16 = Roll 90° + * 17 = Roll 90°, Yaw 45° + * 18 = Roll 90°, Yaw 90° + * 19 = Roll 90°, Yaw 135° + * 20 = Roll 270° + * 21 = Roll 270°, Yaw 45° + * 22 = Roll 270°, Yaw 90° + * 23 = Roll 270°, Yaw 135° + * 24 = Pitch 90° + * 25 = Pitch 270° + * + * @group Sensor Calibration + */ PARAM_DEFINE_INT32(SENS_BOARD_ROT, 0); + +/** + * External magnetometer rotation + * + * This parameter defines the rotation of the external magnetometer relative + * to the platform (not relative to the FMU). + * See SENS_BOARD_ROT for possible values. + * + * @group Sensor Calibration + */ PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0); + /** * RC Channel 1 Minimum * @@ -367,20 +463,52 @@ PARAM_DEFINE_FLOAT(RC18_DZ, 0.0f); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ #endif -PARAM_DEFINE_INT32(RC_DSM_BIND, -1); /* -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind */ +/** + * DSM binding trigger. + * + * -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind + * + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_DSM_BIND, -1); + + +/** + * Scaling factor for battery voltage sensor on PX4IO. + * + * @group Battery Calibration + */ PARAM_DEFINE_INT32(BAT_V_SCALE_IO, 10000); + #ifdef CONFIG_ARCH_BOARD_PX4FMU_V2 +/** + * Scaling factor for battery voltage sensor on FMU v2. + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.0082f); #else -/* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ -/* PX4IOAR: 0.00838095238 */ -/* FMU standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 */ -/* FMU with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) */ +/** + * Scaling factor for battery voltage sensor on FMU v1. + * + * FMUv1 standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659 + * FMUv1 with PX4IO: 0.00459340659 + * FMUv1 with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) = 0.00838095238 + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, 0.00459340659f); #endif + +/** + * Scaling factor for battery current sensor. + * + * @group Battery Calibration + */ PARAM_DEFINE_FLOAT(BAT_C_SCALING, 0.0124); /* scaling for 3DR power brick */ + /** * Roll control channel mapping. * @@ -446,22 +574,127 @@ PARAM_DEFINE_INT32(RC_MAP_YAW, 4); * @group Radio Calibration */ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 0); + +/** + * Return switch channel mapping. + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); + +/** + * Assist switch channel mapping. + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 0); + +/** + * Mission switch channel mapping. + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0); //PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); +/** + * Flaps channel mapping. + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0); -PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); /**< default function: camera pitch */ -PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */ -PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); /**< default function: camera azimuth / yaw */ +/** + * Auxiliary switch 1 channel mapping. + * + * Default function: Camera pitch + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_MAP_AUX1, 0); +/** + * Auxiliary switch 2 channel mapping. + * + * Default function: Camera roll + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_MAP_AUX2, 0); /**< default function: camera roll */ + +/** + * Auxiliary switch 3 channel mapping. + * + * Default function: Camera azimuth / yaw + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_MAP_AUX3, 0); + + +/** + * Roll scaling factor + * + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC_SCALE_ROLL, 0.6f); + +/** + * Pitch scaling factor + * + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC_SCALE_PITCH, 0.6f); + +/** + * Yaw scaling factor + * + * @group Radio Calibration + */ PARAM_DEFINE_FLOAT(RC_SCALE_YAW, 2.0f); -PARAM_DEFINE_INT32(RC_FS_CH, 0); /**< RC failsafe channel, 0 = disable */ -PARAM_DEFINE_INT32(RC_FS_MODE, 0); /**< RC failsafe mode: 0 = too low means signal loss, 1 = too high means signal loss */ -PARAM_DEFINE_FLOAT(RC_FS_THR, 800); /**< RC failsafe PWM threshold */ + +/** + * Failsafe channel mapping. + * + * @min 0 + * @max 18 + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_FS_CH, 0); + +/** + * Failsafe channel mode. + * + * 0 = too low means signal loss, + * 1 = too high means signal loss + * + * @min 0 + * @max 1 + * @group Radio Calibration + */ +PARAM_DEFINE_INT32(RC_FS_MODE, 0); + +/** + * Failsafe channel PWM threshold. + * + * @min 0 + * @max 1 + * @group Radio Calibration + */ +PARAM_DEFINE_FLOAT(RC_FS_THR, 800); diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c index 75be090f80..cb35a25413 100644 --- a/src/modules/systemlib/system_params.c +++ b/src/modules/systemlib/system_params.c @@ -40,8 +40,23 @@ #include #include -// Auto-start script with index #n +/** + * Auto-start script index. + * + * Defines the auto-start script used to bootstrap the system. + * + * @group System + */ PARAM_DEFINE_INT32(SYS_AUTOSTART, 0); -// Automatically configure default values +/** + * Automatically configure default values. + * + * Set to 1 to set platform-specific parameters to their default + * values on next system startup. + * + * @min 0 + * @max 1 + * @group System + */ PARAM_DEFINE_INT32(SYS_AUTOCONFIG, 0); From ed3ffc26d69f25dc087a23761cbf0655afeae8c0 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Fri, 14 Feb 2014 02:21:24 +0100 Subject: [PATCH 55/87] Layout fixes for wiki parameter documentation. - Replace newlines in names and comments with a space. - Right align min/max/default values. --- Tools/px4params/dokuwikiout.py | 46 +++++++++++++++++++--------------- 1 file changed, 26 insertions(+), 20 deletions(-) diff --git a/Tools/px4params/dokuwikiout.py b/Tools/px4params/dokuwikiout.py index c5cf65ea60..e02035423d 100644 --- a/Tools/px4params/dokuwikiout.py +++ b/Tools/px4params/dokuwikiout.py @@ -19,34 +19,40 @@ class DokuWikiOutput(output.Output): for group in groups: result += "==== %s ====\n\n" % group.GetName() result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n" - result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n" + result += "^ Name ^ Description ^ Min ^ Max ^ Default ^ Comment ^\n" for param in group.GetParams(): code = param.GetFieldValue("code") name = param.GetFieldValue("short_desc") - name = name.replace("\n", "") - result += "| %s | %s " % (code, name) min_val = param.GetFieldValue("min") - if min_val is not None: - result += " | %s " % min_val - else: - result += " | " max_val = param.GetFieldValue("max") - if max_val is not None: - result += " | %s " % max_val - else: - result += " | " def_val = param.GetFieldValue("default") - if def_val is not None: - result += "| %s " % def_val - else: - result += " | " long_desc = param.GetFieldValue("long_desc") - if long_desc is not None: - long_desc = long_desc.replace("\n", "") - result += "| %s " % long_desc + + name = name.replace("\n", " ") + result += "| %s | %s |" % (code, name) + + if min_val is not None: + result += " %s |" % min_val else: - result += " | " - result += " |\n" + result += " |" + + if max_val is not None: + result += " %s |" % max_val + else: + result += " |" + + if def_val is not None: + result += " %s |" % def_val + else: + result += " |" + + if long_desc is not None: + long_desc = long_desc.replace("\n", " ") + result += " %s |" % long_desc + else: + result += " |" + + result += "\n" result += "\n" post_text = """ From 9e56652d3eda75a2738bcb9eab3ff99ac2aa455b Mon Sep 17 00:00:00 2001 From: Highlander-UA <315u448@ukrpost.net> Date: Sat, 15 Feb 2014 13:34:49 +0200 Subject: [PATCH 56/87] Added comments for L1 control parameters --- .../fw_pos_control_l1_params.c | 193 +++++++++++++++++- 1 file changed, 186 insertions(+), 7 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 512ca7b8ac..9f15a93866 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -120,57 +120,236 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f); PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); +/** + * Controller roll limit + * + * The maximum roll the controller will output. + * + * @unit degrees + * @min 0.0 + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f); - -PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); - - +/* + * Throttle limit max + * + * This is the maximum throttle % that can be used by the controller. + * For overpowered aircraft, this should be reduced to a value that + * provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. + * +*/ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); +/* + * Throttle limit min + * + * This is the minimum throttle % that can be used by the controller. + * For electric aircraft this will normally be set to zero, but can be set + * to a small non-zero value if a folding prop is fitted to prevent the + * prop from folding and unfolding repeatedly in-flight or to provide + * some aerodynamic drag from a turning prop to improve the descent rate. + * + * For aircraft with internal combustion engine this parameter should be set + * for desired idle rpm. +*/ +PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); + +/* + * Throttle limit value before flare + * + * This throttle value will be set as throttle limit at FW_LND_TLALT, + * before arcraft will flare. +*/ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); + +/* + * Maximum climb rate + * + * This is the best climb rate that the aircraft can achieve with + * the throttle set to THR_MAX and the airspeed set to the + * default value. For electric aircraft make sure this number can be + * achieved towards the end of flight when the battery voltage has reduced. + * The setting of this parameter can be checked by commanding a positive + * altitude change of 100m in loiter, RTL or guided mode. If the throttle + * required to climb is close to THR_MAX and the aircraft is maintaining + * airspeed, then this parameter is set correctly. If the airspeed starts + * to reduce, then the parameter is set to high, and if the throttle + * demand required to climb and maintain speed is noticeably less than + * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or + * FW_THR_MAX reduced. +*/ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); +/* + * Minimum descent rate + * + * This is the sink rate of the aircraft with the throttle + * set to THR_MIN and flown at the same airspeed as used + * to measure FW_T_CLMB_MAX. +*/ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); +/* + * Maximum descent rate + * + * This sets the maximum descent rate that the controller will use. + * If this value is too large, the aircraft can over-speed on descent. + * This should be set to a value that can be achieved without + * exceeding the lower pitch angle limit and without over-speeding + * the aircraft. +*/ +PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); + + +/* + * TECS time constant + * + * This is the time constant of the TECS control algorithm (in seconds). + * Smaller values make it faster to respond, larger values make it slower + * to respond. +*/ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); +/* + * Throttle damping factor + * + * This is the damping gain for the throttle demand loop. + * Increase to add damping to correct for oscillations in speed and height. +*/ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); +/* + * Integrator gain + * + * This is the integrator gain on the control loop. + * Increasing this gain increases the speed at which speed + * and height offsets are trimmed out, but reduces damping and + * increases overshoot. +*/ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); +/* + * Maximum vertical acceleration + * + * This is the maximum vertical acceleration (in metres/second^2) + * either up or down that the controller will use to correct speed + * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) + * allows for reasonably aggressive pitch changes if required to recover + * from under-speed conditions. +*/ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); +*/ + * Complementary filter "omega" parameter for height + * + * This is the cross-over frequency (in radians/second) of the complementary + * filter used to fuse vertical acceleration and barometric height to obtain + * an estimate of height rate and height. Increasing this frequency weights + * the solution more towards use of the barometer, whilst reducing it weights + * the solution more towards use of the accelerometer data. + +*/ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); +/* + * Complementary filter "omega" parameter for speed + * + * This is the cross-over frequency (in radians/second) of the complementary + * filter used to fuse longitudinal acceleration and airspeed to obtain an + * improved airspeed estimate. Increasing this frequency weights the solution + * more towards use of the arispeed sensor, whilst reducing it weights the + * solution more towards use of the accelerometer data. +*/ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); +/* + * Roll -> Throttle feedforward + * + * Increasing this gain turn increases the amount of throttle that will + * be used to compensate for the additional drag created by turning. + * Ideally this should be set to approximately 10 x the extra sink rate + * in m/s created by a 45 degree bank turn. Increase this gain if + * the aircraft initially loses energy in turns and reduce if the + * aircraft initially gains energy in turns. Efficient high aspect-ratio + * aircraft (eg powered sailplanes) can use a lower value, whereas + * inefficient low aspect-ratio models (eg delta wings) can use a higher value. +*/ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); +/* + * Speed <--> Altitude priority + * + * This parameter adjusts the amount of weighting that the pitch control + * applies to speed vs height errors. Setting it to 0.0 will cause the + * pitch control to control height and ignore speed errors. This will + * normally improve height accuracy but give larger airspeed errors. + * Setting it to 2.0 will cause the pitch control loop to control speed + * and ignore height errors. This will normally reduce airspeed errors, + * but give larger height errors. The default value of 1.0 allows the pitch + * control to simultaneously control height and speed. + * Note to Glider Pilots – set this parameter to 2.0 (The glider will + * adjust its pitch angle to maintain airspeed, ignoring changes in height). +*/ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); +/* + * Pitch damping factor + * + * This is the damping gain for the pitch demand loop. Increase to add + * damping to correct for oscillations in height. The default value of 0.0 + * will work well provided the pitch to servo controller has been tuned + * properly. +*/ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); - -PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); - +/* + * Height rate P factor +*/ PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); + +/* + * Speed rate P factor +*/ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); +/* + * Landing slope angle +*/ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); + +/* + * Landing slope length +*/ PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); + +/* + * +*/ PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); + +/* + * Landing flare altitude (relative) +*/ PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f); + +/* + * Landing throttle limit altitude (relative) +*/ PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f); + +/* + * Landing heading hold horizontal distance +*/ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); From 480ba491f35019bfe781b1616bc8db71e71f2740 Mon Sep 17 00:00:00 2001 From: Highlander-UA <315u448@ukrpost.net> Date: Sat, 15 Feb 2014 17:27:38 +0200 Subject: [PATCH 57/87] Missing descriptions added for L1 control parameters --- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 9f15a93866..e0b8d8771a 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -247,7 +247,7 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); -*/ +/* * Complementary filter "omega" parameter for height * * This is the cross-over frequency (in radians/second) of the complementary From 28536682aa664b5dae74b96688cc66b919fccffe Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Feb 2014 21:00:48 +0100 Subject: [PATCH 58/87] Fix airspeed sensor --- src/drivers/airspeed/airspeed.cpp | 4 ++-- src/drivers/airspeed/airspeed.h | 2 +- src/drivers/ets_airspeed/ets_airspeed.cpp | 7 ++++--- src/drivers/meas_airspeed/meas_airspeed.cpp | 10 ++++++---- 4 files changed, 13 insertions(+), 10 deletions(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 771f2128f2..524151c90d 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -76,8 +76,8 @@ #include -Airspeed::Airspeed(int bus, int address, unsigned conversion_interval) : - I2C("Airspeed", AIRSPEED_DEVICE_PATH, bus, address, 100000), +Airspeed::Airspeed(int bus, int address, unsigned conversion_interval, const char* path) : + I2C("Airspeed", path, bus, address, 100000), _reports(nullptr), _buffer_overflows(perf_alloc(PC_COUNT, "airspeed_buffer_overflows")), _max_differential_pressure_pa(0), diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h index c27b1bcd80..186602eda8 100644 --- a/src/drivers/airspeed/airspeed.h +++ b/src/drivers/airspeed/airspeed.h @@ -90,7 +90,7 @@ static const int ERROR = -1; class __EXPORT Airspeed : public device::I2C { public: - Airspeed(int bus, int address, unsigned conversion_interval); + Airspeed(int bus, int address, unsigned conversion_interval, const char* path); virtual ~Airspeed(); virtual int init(); diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 8bbef5cfa0..b6e80ce1d0 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -77,6 +77,7 @@ /* I2C bus address */ #define I2C_ADDRESS 0x75 /* 7-bit address. 8-bit address is 0xEA */ +#define ETS_PATH "/dev/ets_airspeed" /* Register address */ #define READ_CMD 0x07 /* Read the data */ @@ -93,7 +94,7 @@ class ETSAirspeed : public Airspeed { public: - ETSAirspeed(int bus, int address = I2C_ADDRESS); + ETSAirspeed(int bus, int address = I2C_ADDRESS, const char* path = ETS_PATH); protected: @@ -112,8 +113,8 @@ protected: */ extern "C" __EXPORT int ets_airspeed_main(int argc, char *argv[]); -ETSAirspeed::ETSAirspeed(int bus, int address) : Airspeed(bus, address, - CONVERSION_INTERVAL) +ETSAirspeed::ETSAirspeed(int bus, int address, const char* path) : Airspeed(bus, address, + CONVERSION_INTERVAL, path) { } diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 05ae21c1f8..c5394d9b49 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -89,8 +89,10 @@ /* I2C bus address is 1010001x */ #define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */ +#define PATH_MS4525 "/dev/ms4525" /* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ #define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ +#define PATH_MS5525 "/dev/ms5525" /* Register address */ #define ADDR_READ_MR 0x00 /* write to this address to start conversion */ @@ -120,8 +122,8 @@ protected: */ extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); -MEASAirspeed::MEASAirspeed(int bus, int address) : Airspeed(bus, address, - CONVERSION_INTERVAL) +MEASAirspeed::MEASAirspeed(int bus, int address, const char* path) : Airspeed(bus, address, + CONVERSION_INTERVAL, path) { } @@ -304,7 +306,7 @@ start(int i2c_bus) errx(1, "already started"); /* create the driver, try the MS4525DO first */ - g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO); + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS4525DO, PATH_MS4525); /* check if the MS4525DO was instantiated */ if (g_dev == nullptr) @@ -313,7 +315,7 @@ start(int i2c_bus) /* try the MS5525DSO next if init fails */ if (OK != g_dev->Airspeed::init()) { delete g_dev; - g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO); + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO, PATH_MS4425); /* check if the MS5525DSO was instantiated */ if (g_dev == nullptr) From 4bd83dcaeb48cb6629d205b28532f49ca9440e1c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Feb 2014 21:20:02 +0100 Subject: [PATCH 59/87] Fix compile errors --- src/drivers/meas_airspeed/meas_airspeed.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index c5394d9b49..eb65c049be 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -103,7 +103,7 @@ class MEASAirspeed : public Airspeed { public: - MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO); + MEASAirspeed(int bus, int address = I2C_ADDRESS_MS4525DO, const char* path = PATH_MS4525); protected: @@ -315,7 +315,7 @@ start(int i2c_bus) /* try the MS5525DSO next if init fails */ if (OK != g_dev->Airspeed::init()) { delete g_dev; - g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO, PATH_MS4425); + g_dev = new MEASAirspeed(i2c_bus, I2C_ADDRESS_MS5525DSO, PATH_MS5525); /* check if the MS5525DSO was instantiated */ if (g_dev == nullptr) From 2e4c26c9577d11a3ff0e838ffa2c25c4f4ec1452 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sat, 15 Feb 2014 21:12:15 +0100 Subject: [PATCH 60/87] Rename parser.py to srcparser.py to prevent naming conflicts with built-in Python parser library. --- Tools/px4params/px_process_params.py | 4 ++-- Tools/px4params/{parser.py => srcparser.py} | 0 2 files changed, 2 insertions(+), 2 deletions(-) rename Tools/px4params/{parser.py => srcparser.py} (100%) diff --git a/Tools/px4params/px_process_params.py b/Tools/px4params/px_process_params.py index cdf5aba7c0..4f498026fa 100755 --- a/Tools/px4params/px_process_params.py +++ b/Tools/px4params/px_process_params.py @@ -40,12 +40,12 @@ # import scanner -import parser +import srcparser import xmlout import dokuwikiout # Initialize parser -prs = parser.Parser() +prs = srcparser.Parser() # Scan directories, and parse the files sc = scanner.Scanner() diff --git a/Tools/px4params/parser.py b/Tools/px4params/srcparser.py similarity index 100% rename from Tools/px4params/parser.py rename to Tools/px4params/srcparser.py From 1a7518a4224082cf707585a93eb6d934127e5d9e Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sat, 15 Feb 2014 21:18:26 +0100 Subject: [PATCH 61/87] Fixes for Python 3: Use sorted() with key parameter instead of deprecated (and removed) cmp() function. --- Tools/px4params/srcparser.py | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py index 251be672f2..1b2d301108 100644 --- a/Tools/px4params/srcparser.py +++ b/Tools/px4params/srcparser.py @@ -28,8 +28,7 @@ class ParameterGroup(object): state of the parser. """ return sorted(self.params, - cmp=lambda x, y: cmp(x.GetFieldValue("code"), - y.GetFieldValue("code"))) + key=lambda x: x.GetFieldValue("code")) class Parameter(object): """ @@ -61,9 +60,10 @@ class Parameter(object): """ Return list of existing field codes in convenient order """ - return sorted(self.fields.keys(), - cmp=lambda x, y: cmp(self.priority.get(y, 0), - self.priority.get(x, 0)) or cmp(x, y)) + keys = self.fields.keys() + keys = sorted(keys) + keys = sorted(keys, key=lambda x: self.priority.get(x, 0), reverse=True) + return keys def GetFieldValue(self, code): """ @@ -197,7 +197,7 @@ class Parser(object): if tag == "group": group = tags[tag] elif tag not in self.valid_tags: - sys.stderr.write("Skipping invalid" + sys.stderr.write("Skipping invalid " "documentation tag: '%s'\n" % tag) else: param.SetField(tag, tags[tag]) @@ -214,7 +214,7 @@ class Parser(object): object. Note that returned object is not a copy. Modifications affect state of the parser. """ - return sorted(self.param_groups.values(), - cmp=lambda x, y: cmp(self.priority.get(y.GetName(), 0), - self.priority.get(x.GetName(), 0)) or cmp(x.GetName(), - y.GetName())) + groups = self.param_groups.values() + groups = sorted(groups, key=lambda x: x.GetName()) + groups = sorted(groups, key=lambda x: self.priority.get(x.GetName(), 0), reverse=True) + return groups From d30335cb3f141fe0abf7ea853d5e5b097452a0a3 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sat, 15 Feb 2014 21:24:53 +0100 Subject: [PATCH 62/87] Fixes for Python 3 and refactoring: Merge generic Output class into specialized output classes as some need to write files in binary mode. --- Tools/px4params/.gitignore | 1 + Tools/px4params/output.py | 5 -- ...istings.py => output_dokuwiki_listings.py} | 11 ++-- ...kuwikiout.py => output_dokuwiki_tables.py} | 63 ++++++++++--------- Tools/px4params/{xmlout.py => output_xml.py} | 11 ++-- Tools/px4params/px_process_params.py | 22 ++++--- Tools/px4params/xmlrpc.sh | 2 +- 7 files changed, 65 insertions(+), 50 deletions(-) delete mode 100644 Tools/px4params/output.py rename Tools/px4params/{dokuwikiout_listings.py => output_dokuwiki_listings.py} (84%) rename Tools/px4params/{dokuwikiout.py => output_dokuwiki_tables.py} (62%) rename Tools/px4params/{xmlout.py => output_xml.py} (78%) diff --git a/Tools/px4params/.gitignore b/Tools/px4params/.gitignore index 5d0378b4a2..d78b71a6e8 100644 --- a/Tools/px4params/.gitignore +++ b/Tools/px4params/.gitignore @@ -1,3 +1,4 @@ parameters.wiki parameters.xml +parameters.wikirpc.xml cookies.txt \ No newline at end of file diff --git a/Tools/px4params/output.py b/Tools/px4params/output.py deleted file mode 100644 index c092468713..0000000000 --- a/Tools/px4params/output.py +++ /dev/null @@ -1,5 +0,0 @@ -class Output(object): - def Save(self, groups, fn): - data = self.Generate(groups) - with open(fn, 'w') as f: - f.write(data) diff --git a/Tools/px4params/dokuwikiout_listings.py b/Tools/px4params/output_dokuwiki_listings.py similarity index 84% rename from Tools/px4params/dokuwikiout_listings.py rename to Tools/px4params/output_dokuwiki_listings.py index 33f76b415e..117f4edf43 100644 --- a/Tools/px4params/dokuwikiout_listings.py +++ b/Tools/px4params/output_dokuwiki_listings.py @@ -1,7 +1,6 @@ -import output -class DokuWikiOutput(output.Output): - def Generate(self, groups): +class DokuWikiListingsOutput(): + def __init__(self, groups): result = "" for group in groups: result += "==== %s ====\n\n" % group.GetName() @@ -24,4 +23,8 @@ class DokuWikiOutput(output.Output): if def_val is not None: result += "* Default value: %s\n" % def_val result += "\n" - return result + self.output = result + + def Save(self, filename): + with open(filename, 'w') as f: + f.write(self.output) diff --git a/Tools/px4params/dokuwikiout.py b/Tools/px4params/output_dokuwiki_tables.py similarity index 62% rename from Tools/px4params/dokuwikiout.py rename to Tools/px4params/output_dokuwiki_tables.py index e02035423d..dca3fd92d7 100644 --- a/Tools/px4params/dokuwikiout.py +++ b/Tools/px4params/output_dokuwiki_tables.py @@ -1,21 +1,8 @@ -import output from xml.sax.saxutils import escape -class DokuWikiOutput(output.Output): - def Generate(self, groups): - pre_text = """ - - wiki.putPage - - - - :firmware:parameters - - - - - """ - result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values." +class DokuWikiTablesOutput(): + def __init__(self, groups): + result = "====== Parameter Reference ======\nThis list is auto-generated every few minutes and contains the most recent parameter names and default values.\n\n" for group in groups: result += "==== %s ====\n\n" % group.GetName() result += "|< 100% 20% 20% 10% 10% 10% 30%>|\n" @@ -54,15 +41,35 @@ class DokuWikiOutput(output.Output): result += "\n" result += "\n" - post_text = """ - - - - - sum - Updated parameters automagically from code. - - - - """ - return pre_text + escape(result) + post_text + self.output = result; + + def Save(self, filename): + with open(filename, 'w') as f: + f.write(self.output) + + def SaveRpc(self, filename): + with open(filename, 'w') as f: + f.write(""" + + wiki.putPage + + + + :firmware:parameters + + + + + """) + f.write(escape(self.output)) + f.write(""" + + + + + sum + Updated parameters automagically from code. + + + +""") diff --git a/Tools/px4params/xmlout.py b/Tools/px4params/output_xml.py similarity index 78% rename from Tools/px4params/xmlout.py rename to Tools/px4params/output_xml.py index d56802b158..5576954c09 100644 --- a/Tools/px4params/xmlout.py +++ b/Tools/px4params/output_xml.py @@ -1,8 +1,7 @@ -import output from xml.dom.minidom import getDOMImplementation -class XMLOutput(output.Output): - def Generate(self, groups): +class XMLOutput(): + def __init__(self, groups): impl = getDOMImplementation() xml_document = impl.createDocument(None, "parameters", None) xml_parameters = xml_document.documentElement @@ -19,4 +18,8 @@ class XMLOutput(output.Output): xml_param.appendChild(xml_field) xml_value = xml_document.createTextNode(value) xml_field.appendChild(xml_value) - return xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8") + self.output = xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8") + + def Save(self, filename): + with open(filename, 'wb') as f: + f.write(self.output) diff --git a/Tools/px4params/px_process_params.py b/Tools/px4params/px_process_params.py index 4f498026fa..7799f63484 100755 --- a/Tools/px4params/px_process_params.py +++ b/Tools/px4params/px_process_params.py @@ -41,8 +41,9 @@ import scanner import srcparser -import xmlout -import dokuwikiout +import output_xml +import output_dokuwiki_tables +import output_dokuwiki_listings # Initialize parser prs = srcparser.Parser() @@ -50,12 +51,17 @@ prs = srcparser.Parser() # Scan directories, and parse the files sc = scanner.Scanner() sc.ScanDir("../../src", prs) -output = prs.GetParamGroups() +groups = prs.GetParamGroups() # Output into XML -out = xmlout.XMLOutput() -out.Save(output, "parameters.xml") +out = output_xml.XMLOutput(groups) +out.Save("parameters.xml") -# Output into DokuWiki -out = dokuwikiout.DokuWikiOutput() -out.Save(output, "parameters.wiki") +# Output to DokuWiki listings +#out = output_dokuwiki_listings.DokuWikiListingsOutput(groups) +#out.Save("parameters.wiki") + +# Output to DokuWiki tables +out = output_dokuwiki_tables.DokuWikiTablesOutput(groups) +out.Save("parameters.wiki") +out.SaveRpc("parameters.wikirpc.xml") diff --git a/Tools/px4params/xmlrpc.sh b/Tools/px4params/xmlrpc.sh index 36c52ff714..efd177f46a 100644 --- a/Tools/px4params/xmlrpc.sh +++ b/Tools/px4params/xmlrpc.sh @@ -2,4 +2,4 @@ python px_process_params.py rm cookies.txt curl --cookie cookies.txt --cookie-jar cookies.txt --user-agent Mozilla/4.0 --data "u=$XMLRPCUSER&p=$XMLRPCPASS" https://pixhawk.org/start?do=login -curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wiki "https://pixhawk.org/lib/exe/xmlrpc.php" +curl -k --cookie cookies.txt -H "Content-Type: application/xml" -X POST --data-binary @parameters.wikirpc.xml "https://pixhawk.org/lib/exe/xmlrpc.php" From d811853d4463279556f596c7fb064ba016a83acd Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sat, 15 Feb 2014 21:47:13 +0100 Subject: [PATCH 63/87] Fixed Doxygen comments and added parameter documentation group. --- .../fw_pos_control_l1_params.c | 153 +++++++++++------- 1 file changed, 91 insertions(+), 62 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index e0b8d8771a..416a6fcfce 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -40,12 +40,10 @@ */ #include - #include /* * Controller parameters, accessible via MAVLink - * */ /** @@ -119,7 +117,6 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MIN, -45.0f); */ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); - /** * Controller roll limit * @@ -131,17 +128,18 @@ PARAM_DEFINE_FLOAT(FW_P_LIM_MAX, 45.0f); */ PARAM_DEFINE_FLOAT(FW_R_LIM, 45.0f); -/* +/** * Throttle limit max * * This is the maximum throttle % that can be used by the controller. * For overpowered aircraft, this should be reduced to a value that * provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX. * -*/ + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); -/* +/** * Throttle limit min * * This is the minimum throttle % that can be used by the controller. @@ -152,19 +150,22 @@ PARAM_DEFINE_FLOAT(FW_THR_MAX, 1.0f); * * For aircraft with internal combustion engine this parameter should be set * for desired idle rpm. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); -/* +/** * Throttle limit value before flare * * This throttle value will be set as throttle limit at FW_LND_TLALT, * before arcraft will flare. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); - -/* +/** * Maximum climb rate * * This is the best climb rate that the aircraft can achieve with @@ -179,21 +180,23 @@ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); * demand required to climb and maintain speed is noticeably less than * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or * FW_THR_MAX reduced. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); - -/* +/** * Minimum descent rate * * This is the sink rate of the aircraft with the throttle * set to THR_MIN and flown at the same airspeed as used * to measure FW_T_CLMB_MAX. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); - -/* +/** * Maximum descent rate * * This sets the maximum descent rate that the controller will use. @@ -201,41 +204,45 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); * This should be set to a value that can be achieved without * exceeding the lower pitch angle limit and without over-speeding * the aircraft. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); - -/* +/** * TECS time constant * * This is the time constant of the TECS control algorithm (in seconds). * Smaller values make it faster to respond, larger values make it slower * to respond. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); - -/* +/** * Throttle damping factor * * This is the damping gain for the throttle demand loop. * Increase to add damping to correct for oscillations in speed and height. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); - -/* +/** * Integrator gain * * This is the integrator gain on the control loop. * Increasing this gain increases the speed at which speed * and height offsets are trimmed out, but reduces damping and * increases overshoot. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); - -/* +/** * Maximum vertical acceleration * * This is the maximum vertical acceleration (in metres/second^2) @@ -243,11 +250,12 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) * allows for reasonably aggressive pitch changes if required to recover * from under-speed conditions. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); - -/* +/** * Complementary filter "omega" parameter for height * * This is the cross-over frequency (in radians/second) of the complementary @@ -255,12 +263,12 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); * an estimate of height rate and height. Increasing this frequency weights * the solution more towards use of the barometer, whilst reducing it weights * the solution more towards use of the accelerometer data. - -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); - -/* +/** * Complementary filter "omega" parameter for speed * * This is the cross-over frequency (in radians/second) of the complementary @@ -268,11 +276,12 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); * improved airspeed estimate. Increasing this frequency weights the solution * more towards use of the arispeed sensor, whilst reducing it weights the * solution more towards use of the accelerometer data. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); - -/* +/** * Roll -> Throttle feedforward * * Increasing this gain turn increases the amount of throttle that will @@ -283,11 +292,12 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); * aircraft initially gains energy in turns. Efficient high aspect-ratio * aircraft (eg powered sailplanes) can use a lower value, whereas * inefficient low aspect-ratio models (eg delta wings) can use a higher value. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); - -/* +/** * Speed <--> Altitude priority * * This parameter adjusts the amount of weighting that the pitch control @@ -300,56 +310,75 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); * control to simultaneously control height and speed. * Note to Glider Pilots – set this parameter to 2.0 (The glider will * adjust its pitch angle to maintain airspeed, ignoring changes in height). -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); - -/* +/** * Pitch damping factor * * This is the damping gain for the pitch demand loop. Increase to add * damping to correct for oscillations in height. The default value of 0.0 * will work well provided the pitch to servo controller has been tuned * properly. -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); -/* +/** * Height rate P factor -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); -/* +/** * Speed rate P factor -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); -/* +/** * Landing slope angle -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_ANG, 5.0f); -/* +/** * Landing slope length -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_SLLR, 0.9f); -/* +/** * -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_HVIRT, 10.0f); -/* +/** * Landing flare altitude (relative) -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_FLALT, 15.0f); -/* +/** * Landing throttle limit altitude (relative) -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_TLALT, 5.0f); -/* +/** * Landing heading hold horizontal distance -*/ + * + * @group L1 Control + */ PARAM_DEFINE_FLOAT(FW_LND_HHDIST, 15.0f); From 387bfad1cacc2f9929e7590130ca93f27c688655 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Feb 2014 22:19:14 +0100 Subject: [PATCH 64/87] Fixed status printing for airspeed sensor --- src/drivers/meas_airspeed/meas_airspeed.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 05ae21c1f8..6fe6c22212 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -50,6 +50,7 @@ * - Interfacing to MEAS Digital Pressure Modules (http://www.meas-spec.com/downloads/Interfacing_to_MEAS_Digital_Pressure_Modules.pdf) */ + #include #include @@ -386,7 +387,7 @@ test() err(1, "immediate read failed"); warnx("single read"); - warnx("diff pressure: %d pa", (double)report.differential_pressure_pa); + warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa); /* start the sensor polling at 2Hz */ if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) @@ -411,7 +412,7 @@ test() err(1, "periodic read failed"); warnx("periodic read %u", i); - warnx("diff pressure: %d pa", report.differential_pressure_pa); + warnx("diff pressure: %8.4f pa", (double)report.differential_pressure_pa); warnx("temperature: %d C (0x%02x)", (int)report.temperature, (unsigned) report.temperature); } From 1c13225b194583945324d247b83a5236e665d919 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sun, 16 Feb 2014 01:45:10 +0100 Subject: [PATCH 65/87] Fixed illegal character 0x96. --- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 416a6fcfce..62a340e905 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -308,7 +308,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); * and ignore height errors. This will normally reduce airspeed errors, * but give larger height errors. The default value of 1.0 allows the pitch * control to simultaneously control height and speed. - * Note to Glider Pilots – set this parameter to 2.0 (The glider will + * Note to Glider Pilots - set this parameter to 2.0 (The glider will * adjust its pitch angle to maintain airspeed, ignoring changes in height). * * @group L1 Control From 49cc0bd162b63b188c341aab4be880776d21c388 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Sun, 16 Feb 2014 01:47:11 +0100 Subject: [PATCH 66/87] Explicitly treat all files as UTF-8. --- Tools/px4params/output_dokuwiki_listings.py | 3 ++- Tools/px4params/output_dokuwiki_tables.py | 5 +++-- Tools/px4params/output_xml.py | 7 ++++--- Tools/px4params/scanner.py | 3 ++- 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/Tools/px4params/output_dokuwiki_listings.py b/Tools/px4params/output_dokuwiki_listings.py index 117f4edf43..83c50ae15d 100644 --- a/Tools/px4params/output_dokuwiki_listings.py +++ b/Tools/px4params/output_dokuwiki_listings.py @@ -1,3 +1,4 @@ +import codecs class DokuWikiListingsOutput(): def __init__(self, groups): @@ -26,5 +27,5 @@ class DokuWikiListingsOutput(): self.output = result def Save(self, filename): - with open(filename, 'w') as f: + with codecs.open(filename, 'w', 'utf-8') as f: f.write(self.output) diff --git a/Tools/px4params/output_dokuwiki_tables.py b/Tools/px4params/output_dokuwiki_tables.py index dca3fd92d7..aa04304df7 100644 --- a/Tools/px4params/output_dokuwiki_tables.py +++ b/Tools/px4params/output_dokuwiki_tables.py @@ -1,4 +1,5 @@ from xml.sax.saxutils import escape +import codecs class DokuWikiTablesOutput(): def __init__(self, groups): @@ -44,11 +45,11 @@ class DokuWikiTablesOutput(): self.output = result; def Save(self, filename): - with open(filename, 'w') as f: + with codecs.open(filename, 'w', 'utf-8') as f: f.write(self.output) def SaveRpc(self, filename): - with open(filename, 'w') as f: + with codecs.open(filename, 'w', 'utf-8') as f: f.write(""" wiki.putPage diff --git a/Tools/px4params/output_xml.py b/Tools/px4params/output_xml.py index 5576954c09..e845cd1b10 100644 --- a/Tools/px4params/output_xml.py +++ b/Tools/px4params/output_xml.py @@ -1,4 +1,5 @@ from xml.dom.minidom import getDOMImplementation +import codecs class XMLOutput(): def __init__(self, groups): @@ -18,8 +19,8 @@ class XMLOutput(): xml_param.appendChild(xml_field) xml_value = xml_document.createTextNode(value) xml_field.appendChild(xml_value) - self.output = xml_document.toprettyxml(indent=" ", newl="\n", encoding="utf-8") + self.xml_document = xml_document def Save(self, filename): - with open(filename, 'wb') as f: - f.write(self.output) + with codecs.open(filename, 'w', 'utf-8') as f: + self.xml_document.writexml(f, indent=" ", addindent=" ", newl="\n") diff --git a/Tools/px4params/scanner.py b/Tools/px4params/scanner.py index b5a1af47c3..8779b7bbf6 100644 --- a/Tools/px4params/scanner.py +++ b/Tools/px4params/scanner.py @@ -1,5 +1,6 @@ import os import re +import codecs class Scanner(object): """ @@ -29,6 +30,6 @@ class Scanner(object): Scans provided file and passes its contents to the parser using parser.Parse method. """ - with open(path, 'r') as f: + with codecs.open(path, 'r', 'utf-8') as f: contents = f.read() parser.Parse(contents) From 1be3ea4f4eac121a627c194fefbf202586f6f66f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 16 Feb 2014 12:18:22 +0100 Subject: [PATCH 67/87] MPU6000: gyro topic was not initialized --- src/drivers/mpu6000/mpu6000.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index bf80c9cff2..ac75682c47 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1353,6 +1353,7 @@ MPU6000::print_info() MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) : CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO), _parent(parent), + _gyro_topic(-1), _gyro_class_instance(-1) { } From a6af669399b8f12e497aff6292ec35dfd541d903 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 14:43:00 +0100 Subject: [PATCH 68/87] navigator: switch to READY instead of LOITER if landed --- src/modules/navigator/navigator_main.cpp | 66 +++++++++++++----------- 1 file changed, 35 insertions(+), 31 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 260356eca9..5952d667fe 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -305,6 +305,12 @@ private: void start_land(); void start_land_home(); + /** + * Fork for state transitions + */ + void request_loiter_or_ready(); + void request_mission_if_available(); + /** * Guards offboard mission */ @@ -699,24 +705,17 @@ Navigator::task_main() } else { /* MISSION switch */ if (_vstatus.mission_switch == MISSION_SWITCH_LOITER) { - dispatch(EVENT_LOITER_REQUESTED); + request_loiter_or_ready(); stick_mode = true; } else if (_vstatus.mission_switch == MISSION_SWITCH_MISSION) { - /* switch to mission only if available */ - if (_mission.current_mission_available()) { - dispatch(EVENT_MISSION_REQUESTED); - - } else { - dispatch(EVENT_LOITER_REQUESTED); - } - + request_mission_if_available(); stick_mode = true; } if (!stick_mode && _vstatus.return_switch == RETURN_SWITCH_NORMAL && myState == NAV_STATE_RTL) { /* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */ - dispatch(EVENT_LOITER_REQUESTED); + request_mission_if_available(); stick_mode = true; } } @@ -733,17 +732,11 @@ Navigator::task_main() break; case NAV_STATE_LOITER: - dispatch(EVENT_LOITER_REQUESTED); + request_loiter_or_ready(); break; case NAV_STATE_MISSION: - if (_mission.current_mission_available()) { - dispatch(EVENT_MISSION_REQUESTED); - - } else { - dispatch(EVENT_LOITER_REQUESTED); - } - + request_mission_if_available(); break; case NAV_STATE_RTL: @@ -770,12 +763,7 @@ Navigator::task_main() } else { /* on first switch to AUTO try mission by default, if none is available fallback to loiter */ if (myState == NAV_STATE_NONE) { - if (_mission.current_mission_available()) { - dispatch(EVENT_MISSION_REQUESTED); - - } else { - dispatch(EVENT_LOITER_REQUESTED); - } + request_mission_if_available(); } } } @@ -1397,6 +1385,28 @@ Navigator::set_rtl_item() _pos_sp_triplet_updated = true; } +void +Navigator::request_loiter_or_ready() +{ + if (_vstatus.condition_landed) { + dispatch(EVENT_READY_REQUESTED); + + } else { + dispatch(EVENT_LOITER_REQUESTED); + } +} + +void +Navigator::request_mission_if_available() +{ + if (_mission.current_mission_available()) { + dispatch(EVENT_MISSION_REQUESTED); + + } else { + request_loiter_or_ready(); + } +} + void Navigator::position_setpoint_from_mission_item(position_setpoint_s *sp, mission_item_s *item) { @@ -1555,13 +1565,7 @@ Navigator::on_mission_item_reached() /* loiter at last waypoint */ _reset_loiter_pos = false; mavlink_log_info(_mavlink_fd, "[navigator] mission completed"); - - if (_vstatus.condition_landed) { - dispatch(EVENT_READY_REQUESTED); - - } else { - dispatch(EVENT_LOITER_REQUESTED); - } + request_loiter_or_ready(); } } else if (myState == NAV_STATE_RTL) { From 92578e1fc3a3b011aa361ecee65d1bcce1593f6b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 19:34:44 +0100 Subject: [PATCH 69/87] navigator: ignore min altitude on MC, loiter always at current altitude --- src/modules/navigator/navigator_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 5952d667fe..577c767a86 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1059,7 +1059,7 @@ Navigator::start_loiter() float min_alt_amsl = _parameters.min_altitude + _home_pos.alt; /* use current altitude if above min altitude set by parameter */ - if (_global_pos.alt < min_alt_amsl) { + if (_global_pos.alt < min_alt_amsl && !_vstatus.is_rotary_wing) { _pos_sp_triplet.current.alt = min_alt_amsl; mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); From 44c095b9e5717c707faa3528b861bad8eb7ac94a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 19:46:57 +0100 Subject: [PATCH 70/87] commander: allow arming from RC with safety enabled in HIL mode --- src/modules/commander/commander.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 8129dddb30..6d14472f36 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -430,7 +430,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe arming_res = TRANSITION_NOT_CHANGED; if (base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { - if ((safety->safety_switch_available && !safety->safety_off) && status->hil_state == HIL_STATE_OFF) { + if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) { print_reject_arm("NOT ARMING: Press safety switch first."); arming_res = TRANSITION_DENIED; @@ -516,7 +516,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe transition_result_t arming_res = TRANSITION_NOT_CHANGED; if (!armed->armed && ((int)(cmd->param1 + 0.5f)) == 1) { - if (safety->safety_switch_available && !safety->safety_off) { + if (safety->safety_switch_available && !safety->safety_off && status->hil_state == HIL_STATE_OFF) { print_reject_arm("NOT ARMING: Press safety switch first."); arming_res = TRANSITION_DENIED; @@ -1156,7 +1156,7 @@ int commander_thread_main(int argc, char *argv[]) if (status.arming_state == ARMING_STATE_STANDBY && sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { - if (safety.safety_switch_available && !safety.safety_off) { + if (safety.safety_switch_available && !safety.safety_off && status.hil_state == HIL_STATE_OFF) { print_reject_arm("NOT ARMING: Press safety switch first."); } else if (status.main_state != MAIN_STATE_MANUAL) { From 7f7ce77d616679aed7a923c37fff8ef7a6261da2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 20:14:39 +0100 Subject: [PATCH 71/87] mc_att_control: parameters descriptions added --- .../mc_att_control/mc_att_control_params.c | 119 ++++++++++++++++++ 1 file changed, 119 insertions(+) diff --git a/src/modules/mc_att_control/mc_att_control_params.c b/src/modules/mc_att_control/mc_att_control_params.c index 27a45b6bbc..488107d585 100644 --- a/src/modules/mc_att_control/mc_att_control_params.c +++ b/src/modules/mc_att_control/mc_att_control_params.c @@ -41,16 +41,135 @@ #include +/** + * Roll P gain + * + * Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f); + +/** + * Roll rate P gain + * + * Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f); + +/** + * Roll rate I gain + * + * Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f); + +/** + * Roll rate D gain + * + * Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.002f); + +/** + * Pitch P gain + * + * Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + * + * @unit 1/s + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f); + +/** + * Pitch rate P gain + * + * Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f); + +/** + * Pitch rate I gain + * + * Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f); + +/** + * Pitch rate D gain + * + * Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.002f); + +/** + * Yaw P gain + * + * Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad. + * + * @unit 1/s + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f); + +/** + * Yaw rate P gain + * + * Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f); + +/** + * Yaw rate I gain + * + * Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f); + +/** + * Yaw rate D gain + * + * Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + * + * @min 0.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f); + +/** + * Yaw feed forward + * + * Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + * + * @min 0.0 + * @max 1.0 + * @group Multicopter Attitude Control + */ PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f); From 4b41a398e71d177661cc5127427448d55bab944e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 21:05:54 +0100 Subject: [PATCH 72/87] mc_pos_control: parameters descriptions added --- .../mc_pos_control/mc_pos_control_params.c | 146 +++++++++++++++++- 1 file changed, 145 insertions(+), 1 deletion(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c index 9eb56545d7..0082a5e6a6 100644 --- a/src/modules/mc_pos_control/mc_pos_control_params.c +++ b/src/modules/mc_pos_control/mc_pos_control_params.c @@ -39,20 +39,164 @@ #include -PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.0f); +/** + * Minimum thrust + * + * Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust. + * + * @min 0.0 + * @max 1.0 + * @group Multicopter Position Control + */ +PARAM_DEFINE_FLOAT(MPC_THR_MIN, 0.1f); + +/** + * Maximum thrust + * + * Limit max allowed thrust. + * + * @min 0.0 + * @max 1.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_THR_MAX, 1.0f); + +/** + * Proportional gain for vertical position error + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_P, 1.0f); + +/** + * Proportional gain for vertical velocity error + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_VEL_P, 0.1f); + +/** + * Integral gain for vertical velocity error + * + * Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff. + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_VEL_I, 0.02f); + +/** + * Differential gain for vertical velocity error + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_VEL_D, 0.0f); + +/** + * Maximum vertical velocity + * + * Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (SEATBELT, EASY). + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_VEL_MAX, 5.0f); + +/** + * Vertical velocity feed forward + * + * Feed forward weight for altitude control in stabilized modes (SEATBELT, EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + * + * @min 0.0 + * @max 1.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_Z_FF, 0.5f); + +/** + * Proportional gain for horizontal position error + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_P, 1.0f); + +/** + * Proportional gain for horizontal velocity error + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_VEL_P, 0.1f); + +/** + * Integral gain for horizontal velocity error + * + * Non-zero value allows to resist wind. + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_VEL_I, 0.02f); + +/** + * Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again. + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_VEL_D, 0.01f); + +/** + * Maximum horizontal velocity + * + * Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (EASY). + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_VEL_MAX, 5.0f); + +/** + * Horizontal velocity feed forward + * + * Feed forward weight for position control in position control mode (EASY). 0 will give slow responce and no overshot, 1 - fast responce and big overshot. + * + * @min 0.0 + * @max 1.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_XY_FF, 0.5f); + +/** + * Maximum tilt + * + * Limits maximum tilt in AUTO and EASY modes. + * + * @min 0.0 + * @max 1.57 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_TILT_MAX, 1.0f); + +/** + * Landing descend rate + * + * @min 0.0 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_LAND_SPEED, 1.0f); + +/** + * Maximum landing tilt + * + * Limits maximum tilt on landing. + * + * @min 0.0 + * @max 1.57 + * @group Multicopter Position Control + */ PARAM_DEFINE_FLOAT(MPC_LAND_TILT, 0.3f); From 2c589ea374da5fc3b368d9195a80bc20365c86d5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 16 Feb 2014 21:11:27 +0100 Subject: [PATCH 73/87] navigator: parameters descriptions cleanup --- src/modules/navigator/navigator_params.c | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index ec7a4e2296..87be737c42 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -53,7 +53,7 @@ */ /** - * Minimum altitude + * Minimum altitude (fixed wing only) * * @group Navigation */ @@ -67,32 +67,36 @@ PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f); PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f); /** - * Loiter radius. + * Loiter radius (fixed wing only) * * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f); /** + * Enable onboard mission. + * * @group Navigation */ PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0); /** - * Default take-off altitude. + * Take-off altitude. + * + * Even if first waypoint has altitude less then NAV_TAKEOFF_ALT, system will climb to NAV_TAKEOFF_ALT on takeoff, then go to waypoint. * * @group Navigation */ -PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); // default TAKEOFF altitude +PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); /** * Landing altitude. * - * Slowly descend from this altitude when landing. + * Stay at this altitude after RTL descending. Slowly descend from this altitude if autolanding allowed. * * @group Navigation */ -PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when landing +PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); /** * Return-to-land altitude. @@ -101,12 +105,12 @@ PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); // slow descend from this altitude when * * @group Navigation */ -PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); // min altitude for going home in RTL mode +PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); /** * Return-to-land delay. * - * Delay after descend before landing. + * Delay after descend before landing in RTL mode. * If set to -1 the system will not land but loiter at NAV_LAND_ALT. * * @group Navigation From 9665d38940dec371be3dd1c5e711a670162e2a30 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 12:51:13 +0400 Subject: [PATCH 74/87] navigator: parameters descriptions cleanup --- src/modules/navigator/navigator_params.c | 37 +++++++++++++++++------- 1 file changed, 26 insertions(+), 11 deletions(-) diff --git a/src/modules/navigator/navigator_params.c b/src/modules/navigator/navigator_params.c index 87be737c42..9ef359c6dc 100644 --- a/src/modules/navigator/navigator_params.c +++ b/src/modules/navigator/navigator_params.c @@ -55,70 +55,85 @@ /** * Minimum altitude (fixed wing only) * + * Minimum altitude above home for LOITER. + * + * @unit meters * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_MIN_ALT, 50.0f); /** - * Waypoint acceptance radius. + * Waypoint acceptance radius * + * Default value of acceptance radius (if not specified in mission item). + * + * @unit meters + * @min 0.0 * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_ACCEPT_RAD, 10.0f); /** - * Loiter radius (fixed wing only) + * Loiter radius (fixed wing only) * + * Default value of loiter radius (if not specified in mission item). + * + * @unit meters + * @min 0.0 * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_LOITER_RAD, 50.0f); /** - * Enable onboard mission. + * Enable onboard mission * * @group Navigation */ PARAM_DEFINE_INT32(NAV_ONB_MIS_EN, 0); /** - * Take-off altitude. + * Take-off altitude * - * Even if first waypoint has altitude less then NAV_TAKEOFF_ALT, system will climb to NAV_TAKEOFF_ALT on takeoff, then go to waypoint. + * Even if first waypoint has altitude less then NAV_TAKEOFF_ALT above home position, system will climb to NAV_TAKEOFF_ALT on takeoff, then go to waypoint. * + * @unit meters * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_TAKEOFF_ALT, 10.0f); /** - * Landing altitude. + * Landing altitude * - * Stay at this altitude after RTL descending. Slowly descend from this altitude if autolanding allowed. + * Stay at this altitude above home position after RTL descending. Land (i.e. slowly descend) from this altitude if autolanding allowed. * + * @unit meters * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_LAND_ALT, 5.0f); /** - * Return-to-land altitude. + * Return-To-Launch altitude * - * Minimum altitude for going home in RTL mode. + * Minimum altitude above home position for going home in RTL mode. * + * @unit meters * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_RTL_ALT, 30.0f); /** - * Return-to-land delay. + * Return-To-Launch delay * * Delay after descend before landing in RTL mode. * If set to -1 the system will not land but loiter at NAV_LAND_ALT. * + * @unit seconds * @group Navigation */ PARAM_DEFINE_FLOAT(NAV_RTL_LAND_T, -1.0f); /** - * Enable parachute deployment. + * Enable parachute deployment * * @group Navigation */ From 7d80f05b4d857b933cf7aca106ac55a7111e3b35 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 12:53:06 +0400 Subject: [PATCH 75/87] mc_att_control: more strict conditions for integrating --- src/modules/mc_att_control/mc_att_control_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index db5e2e9bb0..8de0f0b39f 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -86,7 +86,7 @@ extern "C" __EXPORT int mc_att_control_main(int argc, char *argv[]); #define MIN_TAKEOFF_THROTTLE 0.3f #define YAW_DEADZONE 0.05f -#define RATES_I_LIMIT 0.5f +#define RATES_I_LIMIT 0.3f class MulticopterAttitudeControl { @@ -658,7 +658,7 @@ MulticopterAttitudeControl::control_attitude_rates(float dt) _rates_prev = rates; /* update integral only if not saturated on low limit */ - if (_thrust_sp > 0.1f) { + if (_thrust_sp > 0.2f) { for (int i = 0; i < 3; i++) { if (fabsf(_att_control(i)) < _thrust_sp) { float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt; From 838290fa63cf5592e5c9d7590d0f359f5f81aac3 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 17:12:25 +0400 Subject: [PATCH 76/87] mc_att_control: pref counter name fixed --- src/modules/mc_att_control/mc_att_control_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 8de0f0b39f..38fde0cace 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -262,7 +262,7 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _actuators_0_pub(-1), /* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, "fw att control")) + _loop_perf(perf_alloc(PC_ELAPSED, "mc att control")) { memset(&_v_att, 0, sizeof(_v_att)); From 71d4c7fed8bc809fc38ba54147156fc834d38846 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 5 Feb 2014 19:03:26 +0100 Subject: [PATCH 77/87] Startup: Hex vs Hexa --- ROMFS/px4fmu_common/init.d/rcS | 2 +- ROMFS/px4fmu_common/mixers/{FMU_hex_+.mix => FMU_hexa_+.mix} | 0 ROMFS/px4fmu_common/mixers/{FMU_hex_x.mix => FMU_hexa_x.mix} | 0 3 files changed, 1 insertion(+), 1 deletion(-) rename ROMFS/px4fmu_common/mixers/{FMU_hex_+.mix => FMU_hexa_+.mix} (100%) rename ROMFS/px4fmu_common/mixers/{FMU_hex_x.mix => FMU_hexa_x.mix} (100%) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 50ac9759a5..d127853683 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -465,7 +465,7 @@ then set MAV_TYPE 2 # Use mixer to detect vehicle type - if [ $MIXER == FMU_hex_x -o $MIXER == FMU_hex_+ ] + if [ $MIXER == FMU_hexa_x -o $MIXER == FMU_hexa_+ ] then set MAV_TYPE 13 fi diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix similarity index 100% rename from ROMFS/px4fmu_common/mixers/FMU_hex_+.mix rename to ROMFS/px4fmu_common/mixers/FMU_hexa_+.mix diff --git a/ROMFS/px4fmu_common/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix similarity index 100% rename from ROMFS/px4fmu_common/mixers/FMU_hex_x.mix rename to ROMFS/px4fmu_common/mixers/FMU_hexa_x.mix From e407766cc7c9f2c2d06deb064b9a1c89cb17a203 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:56:31 +0400 Subject: [PATCH 78/87] mc_att_control: minor cleanup and refactoring, move some class attributes to local variables --- .../mc_att_control/mc_att_control_main.cpp | 43 +++++++++---------- 1 file changed, 20 insertions(+), 23 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 38fde0cace..76ee2c311c 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -71,7 +71,6 @@ #include #include #include -#include #include #include #include @@ -84,8 +83,8 @@ */ extern "C" __EXPORT int mc_att_control_main(int argc, char *argv[]); -#define MIN_TAKEOFF_THROTTLE 0.3f #define YAW_DEADZONE 0.05f +#define MIN_TAKEOFF_THRUST 0.2f #define RATES_I_LIMIT 0.3f class MulticopterAttitudeControl @@ -135,15 +134,13 @@ private: perf_counter_t _loop_perf; /**< loop performance counter */ - math::Matrix<3, 3> _R_sp; /**< attitude setpoint rotation matrix */ - math::Matrix<3, 3> _R; /**< rotation matrix for current state */ math::Vector<3> _rates_prev; /**< angular rates on previous step */ math::Vector<3> _rates_sp; /**< angular rates setpoint */ math::Vector<3> _rates_int; /**< angular rates integral error */ float _thrust_sp; /**< thrust setpoint */ math::Vector<3> _att_control; /**< attitude control vector */ - math::Matrix<3, 3> I; /**< identity matrix */ + math::Matrix<3, 3> _I; /**< identity matrix */ bool _reset_yaw_sp; /**< reset yaw setpoint flag */ @@ -262,7 +259,7 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _actuators_0_pub(-1), /* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, "mc att control")) + _loop_perf(perf_alloc(PC_ELAPSED, "mc_att_control")) { memset(&_v_att, 0, sizeof(_v_att)); @@ -276,15 +273,13 @@ MulticopterAttitudeControl::MulticopterAttitudeControl() : _params.rate_i.zero(); _params.rate_d.zero(); - _R_sp.identity(); - _R.identity(); _rates_prev.zero(); _rates_sp.zero(); _rates_int.zero(); _thrust_sp = 0.0f; _att_control.zero(); - I.identity(); + _I.identity(); _params_handles.roll_p = param_find("MC_ROLL_P"); _params_handles.roll_rate_p = param_find("MC_ROLLRATE_P"); @@ -535,16 +530,17 @@ MulticopterAttitudeControl::control_attitude(float dt) _thrust_sp = _v_att_sp.thrust; /* construct attitude setpoint rotation matrix */ + math::Matrix<3, 3> R_sp; if (_v_att_sp.R_valid) { /* rotation matrix in _att_sp is valid, use it */ - _R_sp.set(&_v_att_sp.R_body[0][0]); + R_sp.set(&_v_att_sp.R_body[0][0]); } else { /* rotation matrix in _att_sp is not valid, use euler angles instead */ - _R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); + R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); /* copy rotation matrix back to setpoint struct */ - memcpy(&_v_att_sp.R_body[0][0], &_R_sp.data[0][0], sizeof(_v_att_sp.R_body)); + memcpy(&_v_att_sp.R_body[0][0], &R_sp.data[0][0], sizeof(_v_att_sp.R_body)); _v_att_sp.R_valid = true; } @@ -561,23 +557,24 @@ MulticopterAttitudeControl::control_attitude(float dt) } /* rotation matrix for current state */ - _R.set(_v_att.R); + math::Matrix<3, 3> R; + R.set(_v_att.R); /* all input data is ready, run controller itself */ /* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */ - math::Vector<3> R_z(_R(0, 2), _R(1, 2), _R(2, 2)); - math::Vector<3> R_sp_z(_R_sp(0, 2), _R_sp(1, 2), _R_sp(2, 2)); + math::Vector<3> R_z(R(0, 2), R(1, 2), R(2, 2)); + math::Vector<3> R_sp_z(R_sp(0, 2), R_sp(1, 2), R_sp(2, 2)); /* axis and sin(angle) of desired rotation */ - math::Vector<3> e_R = _R.transposed() * (R_z % R_sp_z); + math::Vector<3> e_R = R.transposed() * (R_z % R_sp_z); /* calculate angle error */ float e_R_z_sin = e_R.length(); float e_R_z_cos = R_z * R_sp_z; /* calculate weight for yaw control */ - float yaw_w = _R_sp(2, 2) * _R_sp(2, 2); + float yaw_w = R_sp(2, 2) * R_sp(2, 2); /* calculate rotation matrix after roll/pitch only rotation */ math::Matrix<3, 3> R_rp; @@ -600,15 +597,15 @@ MulticopterAttitudeControl::control_attitude(float dt) e_R_cp(2, 1) = e_R_z_axis(0); /* rotation matrix for roll/pitch only rotation */ - R_rp = _R * (I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); + R_rp = R * (_I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); } else { /* zero roll/pitch rotation */ - R_rp = _R; + R_rp = R; } - /* R_rp and _R_sp has the same Z axis, calculate yaw error */ - math::Vector<3> R_sp_x(_R_sp(0, 0), _R_sp(1, 0), _R_sp(2, 0)); + /* R_rp and R_sp has the same Z axis, calculate yaw error */ + math::Vector<3> R_sp_x(R_sp(0, 0), R_sp(1, 0), R_sp(2, 0)); math::Vector<3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0)); e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w; @@ -616,7 +613,7 @@ MulticopterAttitudeControl::control_attitude(float dt) /* for large thrust vector rotations use another rotation method: * calculate angle and axis for R -> R_sp rotation directly */ math::Quaternion q; - q.from_dcm(_R.transposed() * _R_sp); + q.from_dcm(R.transposed() * R_sp); math::Vector<3> e_R_d = q.imag(); e_R_d.normalize(); e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0)); @@ -658,7 +655,7 @@ MulticopterAttitudeControl::control_attitude_rates(float dt) _rates_prev = rates; /* update integral only if not saturated on low limit */ - if (_thrust_sp > 0.2f) { + if (_thrust_sp > MIN_TAKEOFF_THRUST) { for (int i = 0; i < 3; i++) { if (fabsf(_att_control(i)) < _thrust_sp) { float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt; From 55f5f1815f6a8f2efb969cea2eb061bdc2d9b92a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:57:23 +0400 Subject: [PATCH 79/87] mc_att_control: remove rate limiting to run at 250Hz --- src/modules/mc_att_control/mc_att_control_main.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 76ee2c311c..e92b7f3758 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -692,9 +692,6 @@ MulticopterAttitudeControl::task_main() _manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); - /* rate limit attitude updates to 200Hz, failsafe against spam, normally runs at the same rate as attitude estimator */ - orb_set_interval(_v_att_sub, 5); - /* initialize parameters cache */ parameters_update(); From 2b4af6635708be2248abf53edb65a9223fedcd6a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:58:13 +0400 Subject: [PATCH 80/87] mc_att_control: poll vehicle_rates_setpoint if attitude controller disabled --- src/modules/mc_att_control/mc_att_control_main.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index e92b7f3758..b5df83d859 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -761,10 +761,12 @@ MulticopterAttitudeControl::task_main() } } else { - /* attitude controller disabled */ - // TODO poll 'attitude_rates_setpoint' topic - _rates_sp.zero(); - _thrust_sp = 0.0f; + /* attitude controller disabled, poll rates setpoint topic */ + vehicle_rates_setpoint_poll(); + _rates_sp(0) = _v_rates_sp.roll; + _rates_sp(1) = _v_rates_sp.pitch; + _rates_sp(2) = _v_rates_sp.yaw; + _thrust_sp = _v_rates_sp.thrust; } if (_v_control_mode.flag_control_rates_enabled) { From 969f564a132e7b14e94028798ca5a4d6c5f13244 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 23:58:58 +0400 Subject: [PATCH 81/87] mc_att_control: code style fixed --- src/modules/mc_att_control/mc_att_control_main.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index b5df83d859..01902ed0cf 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -531,6 +531,7 @@ MulticopterAttitudeControl::control_attitude(float dt) /* construct attitude setpoint rotation matrix */ math::Matrix<3, 3> R_sp; + if (_v_att_sp.R_valid) { /* rotation matrix in _att_sp is valid, use it */ R_sp.set(&_v_att_sp.R_body[0][0]); @@ -762,10 +763,10 @@ MulticopterAttitudeControl::task_main() } else { /* attitude controller disabled, poll rates setpoint topic */ - vehicle_rates_setpoint_poll(); - _rates_sp(0) = _v_rates_sp.roll; - _rates_sp(1) = _v_rates_sp.pitch; - _rates_sp(2) = _v_rates_sp.yaw; + vehicle_rates_setpoint_poll(); + _rates_sp(0) = _v_rates_sp.roll; + _rates_sp(1) = _v_rates_sp.pitch; + _rates_sp(2) = _v_rates_sp.yaw; _thrust_sp = _v_rates_sp.thrust; } From 3eca9f9b6b866e1c7ad8b57d16ad16cb073d6085 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:11:03 +0100 Subject: [PATCH 82/87] Updated logging/conv.zip with latest script versions from Tools directory. --- ROMFS/px4fmu_common/logging/conv.zip | Bin 10087 -> 9922 bytes 1 file changed, 0 insertions(+), 0 deletions(-) diff --git a/ROMFS/px4fmu_common/logging/conv.zip b/ROMFS/px4fmu_common/logging/conv.zip index 7cb837e5666f51eca7ed803dfef4581f01bec1f3..7f485184c6d453a422f795489fe64684e9b179e3 100644 GIT binary patch delta 9806 zcmZ{KQ*fYN*K9JeZQHgrv6G22v27<$Y;)pF>||owp4hf+ocFE2>U`f{bHQiclD7%pS+-wEEqUC$TtvZ5He2V`qL1Zit5OXsS5Eu{;5F2}QV|zO{M%xPk zYx^~+#4V^_Uo-VkAx5I3Udsxkl1W$yWPp!UJ{nIL*wim6^!E0)@_&j@ULis*HC2)E zzGu;Xbosi{RTzGQq?r=N*ID9Qnr21g83egz#{Qy{%T>bir4gvDdmBN9pySc<;~5i$ z)64MA${@xcd~A+6FoMf7l$OQ|NYLn6g7=cOxUC7Thb4Uj-H49$IU>njpXZ%J;MRv5 z$6fMcTpDhq9-kG7fUH&*>h0WK5Hv;MjM0uUKqj{?AyJ~OsmyzzgROJez>+6QA7HTo z6S{7)Tk|-1rEFhkvZ7$Ul&AdY4ZHE%Q5m5`3vVQ(SC$~$m?8Tt0L*a%&eZG^wo+{q zi%tSewht&CZO|Z0O4KWikq*d{xDhD<#dbH*XMIc3-o7R8~*C;PklB#(@5c#nRIh7BcK6)^!%MqkXoIkTLe8Bbrj`HdF!pmQdHTP z1@ijHpJc~1om`E4N)thu`yDi_@w`^zN`J$DD_ttU@mJr-sVfuGja>`C%7|V7df1V_ z6Aijn?}@(Da(djE{dsidvshA;vTW1-xhFTb&^T`u6ylH#aR%CL&;RjhcJYb{`z3#@ z35v(ghV{2L9P7fX#t9w_wAj?6T2p|RSZ~Z%77%LE$;+~6c>hr7r8I~HV9!+5aWbiL zE{Xd~v0)v}Q1M6W4<_jQ!GlYI@007-i=5+szRAC0b!M`RZGf+;sraTFok)|vatUkV zF^#!4#-mPbAS->Fh-YKwMm@(y4gc-mC_hji-}XBUx|w1OV3xbGGf57CIFI3cO#G^I{?Q~7^1(Y4NNvr^%TiRa6n9MNW495(D)2)DjG(coeYbKc1v`S4}ngD4Te30!ML2rYXB)8 zw-ckHWxN$WE$R{cDFSUe`;P*{K()?QZQvc`!TB}n+C8nzH0+E}Gp7eV`67)ST*50zm6e|iEBn)*nJOk6I25txKgmw4uMlyc zB|;prys8xHsbJy3Ltq*i-Yk_21p~FR7o7ZrxzN`|ltep>&2gh7P;u+A3xtHuRo-Aj z0jUIIYznH?3HE%vCW_>E+7ZCINA!WcJgB@>W;@Dh|3=j*V>KBhQMFmAB6YikEGz}q zg0#~QS+Ds`>26C5fU}#fd|59X%AQUQ=r4Jy_?o`Vow}q}8uemWo~XR|{MEl5$w?ejQ@4w=WX zLO1Pg&82tLMXUgKwT458RSlj4i74jzaC<~c=vH=mQ)3_SH{)2+H?P%nm8~O2A=^R( z_zVq|n(-GZ4+W@jcW#GZ0?;kco|a2EsABPwC!xlX#!%p6sGo~UY0p9cL3l`jm081d zw?<%@{K(W4L4-QoUkL0Km#f~PvAUXQG*{*`SITs%8|;z8SRc`k2DeC)Y&M$35|>Oj zYDPU`ECGNNQh~-Y=z_8S8&VB|;Iaxm&i0_SuH#?W03(FM3t8`3R}lJcuA^}-@hqDr z{>?d)7R89DSyfwf>W?l`me;`cw2e*8__MMHG$VKu5m747dzx##Q`Skd%)=d0taWS8 zv$#0Cw{)zvO7}Bt|I{tJ_C1>fD?LwoNY2!RnkBGEJ1K?Jamvj6ff?8LBZTQZ5(t_z zrgyE;ttnfQ&Z(1DQZ7Xw|4rdx^*NiRma?x&i`-;yWJ;cEe(MsIvDD;VH4>Jy)M*{(HWIB1*2J9l%nTkHhFX+@J%#;YfCE zv$?QnFS5A$5UP}rZm+`@KjT(_xxs3_{kM55d`ot*Xk(;&!6~MGek}|cK4rOaea3>z z0NL7N1Yy$cjsoiK^qKct7ipbe5l<5 z%JxI0&+{GJCzzg#YkOfm04uFMv7rqk#~DN2M6R()ye-iZ<2y@CW#qcLg(IJ?9=5am zO^~FFj)5Tf%h`mQ_A-{R8-CAbM?8=kseNm3s^5&Bo(#^%aZqrkwPj$paoLk|S!uyE z$axe%Ub${}E}G^V6veC;oLsCFMHXKY?6Ay2v0%l~LElwKEHz8%;_YI45M(-*2x^?6sj%X>aVphRxBZ`1afoN&J2iP2RVVl zoi40`DoDgW54uj6Tcx@?;_y+lt|qtQYIzRn!LmxqaVqs|mKS60xNmRw^-tI=HU8Ay zc`FiM`101uQ9;RZkhg^DZWrTQl)f+^9fH{`rUL22rHlBXvy$6&PP|?Ann-#9lMy6+ zSNK@VCmIwiAw3R5Cce}sLk^I8Ky8FjaEm*zXdNbf#nS^wH;-_v(>3E)$H_;- zswqzED!n9^Kr>~QaMOq%#zAzM+lNivwx^_QY-bu&^5Q1w{z*EmeN}x;$mAzqM68l- z_4Xs`@i}#%n+7H-(eL?%RQZ{|PR%E(3B~z6e}KE zl8qiT+MX8fuMsh6j8VAIz3Y1$RJ8lH4lHAY$)R$Sb};FHkcFS1v{fUjGO%if&2rHu zrmWyuwgxHT;}sa}$3`XXwaC#NNXl{;L7F5V&VU2&yWAeK9w4;kW7 zKR+CslaWejJD%cRZd-=$0BFzkcKdOF^P4FEZ%4nO?L|gg98HfS);RcSReVA5`>$f55**inY?@=DYywqDwA4ghSgQtlz0>N8CwzHUzrnHg5J>SN+qfyQR zQG*pEjf07FE^KG#YA933`3j0yud?#juHr;2CMhl6CF%v<6R+8qUGH!S)w*-V^h?v% ztE_=*LTkPQ6R64y2cP48N`=^o3NieZCXXu}g$ zE4TM-6~~y0J1=VNoAqTcas2QxIS&(K37j!S2(?|UGg!dBD_Odoex&Q0jzTkaeFie1 zDvTO95Mm5@39I=1&E!=C$yW#ya!t2~b?k#B=mz?$i^kK03odDcC7RSkteI)B4TGvZ zLdF0a`HwfsMg`bcH&?>Oy7Z%=VVw}ammNympRKgOk4RO&a5or<=g{`h4cF6?`kt-M%}|V z@$d^&w?q=Q++lZaI1F-Zlkxg!YUtnUsTXh&Ixi($ZlE$*^CR^4f8F@LR4Z?h#OaET zIM*EgmBzq@w4{YL={3I3I^;c>?XNx}4i4I-sT=(Tu5h>II>}la2o7Q&lPX@>|>KSrS!l1aQ$Khb9mQ z7nmXm$}UKC^DOnw6kP3^`E~jDfKKcGbPXaDdZ@(Iq_No?2KK5RK|(YCg?FJ zK7QKufXbPhW5 zSedhtbso$nfy$ca+Zb{#-|De^7;ik5W>6ssWctQS8P+YT;rOK{u&a5l|DAbUU(N3w zqlWgqTxFUY`}Wn4GRj6bi3lGDXvE_eV9b_|6<-Tfdk&K3%*_Z7TV$mk_ev;dmM+TM z(cd9cWy|73w1$c)AWM8LuID$-sP^W-eSk!Z|F|r5=Ili`y(&p@;uNYHNOQCc@W54p zLCzG#@+Xz05WCGKd3Uzr&V6eANF5AXZCO7s;lG&p{kl1R7YR>iqZwSD zw^Q{{rMt@s7nJ|#gZCG^CW-V8w2YCLYoEdTbm>h(>1l?toa%UwD95B-qs8@Hhddcq zCH7r|Jh4YlOr&USjWEdo60gN6jp!!nJ?oG%wERqo*z3{d1SiArT)~o1lyU#*@H^Kb z<$F4r68*S)mla%*#7oNvJ7gz>D&HgS7QZ!^6U4Mh(xZ#G<2pNi7pmr%t zAgedVUfgG;Knz&;5w4xQ!p^)3of#Im1&41`5tCc>}7ebEqfB2^!1T)Iu#Aix5$#69bcl|xDI11-+C_5C(iJ4OSz zQ-A{{(vXRlcMsI$SG_#;$8SZgSkz(O0Zt8A)WhBZw_eQyhdtv7%gry88sDSX(M=aI zNhjW8NHD@xJ4Q^b?P+opF14L%lbw}V5PxxhmVse<`yC@>n?(oKVDjQnKikM`Tp6O70R|O+F6cqfA*X6NsNNt+EOA+0DrB9r?6IEd@ z2pDk!4c!H8pZBv*XtL+i%p!Hqi8Qrafs9#Te1dx-3J}wX3Dh0a({D2v7`>M7fp|8~ z6W-c6c8a;^&ItndQ+K`9#tEPtMGr46fz?2lHJ6Cp!~(C!x{Aecl0;SUDrTXyDY;6Y zyQVS-@!T1Q13XWU-jOJ$f4{jLnumq!1IG8p6&zCMuv?r68t)Pm#jG8gVeorQ;W-s| z+;l!ot3eK;ySuK~vtR7E18gD=$}xWTW^hTE2q%_ye$MdZ{)O|2#nQ{k!5%XM%IQEE z={Pd?A(*dzz%eKt2229Cb+F_Q^J4pk-dbE@2-x++cj;6VvHH{T6uI&4Ia})?g@n|D zz3N*&h-X>E3F3u=;N)f7z*$0~%t7%<9^oh=MOk_a#W7TiEzdm4s;$73(R0_`)*6rT z9j^H#bH9woL@K?P6Fq)fq&q6aaaEvq$Ns?Thndr(Q_YBtOo&}FRk?GI83%)S{to$~ zu3PMg_RG6SH+8*?HDm;;JE~MBLGR(2$nz7&U#FdIvhMtrIIj$kNpOOAkQ@&af00+A z+}X}!Bt~9f`;A_z+1c;YyX0*t*PT`92q*2<$>R-avIC5>pYYE9a>@OpcL8{Q_id2h z3{MlZ^VmO3V$7Y(1AETIBvtk! z8qaB_^pr$3g`Wwo3%>SN_9y;&r=pP!??ih*;b8F1gn*uLTq&?d2NQF@PCjMmDs=tB zEa3B0PFDL8<70GX)j8}gZU6{@X=6Rd#^RGq;FJC?yjzkon+{0E{R`&8LiAllz!1Yk z9ojpcecqcSBj{6JcgEemuPNdaBDV{B|v_^hjoTKjH<}WQZ!*%%<_{T z*;7l$JNA>uPsT$+S60|RaR|QO-dYZ&N9>LC?atI6DfF0r6#q;QmGJ>qVtWo3Ql>)@ zYf)q9LDVOEw)!U*W_lw!lN!bfN)%3{i#wnuR2QXX)xLk&rb_cO(`Zp+x}bjIyN4jG zzZ&pCrQE8%Pb&T$ueUp+71(Pnfw~`!6Zk!C-MSpql@i*?GmPYN9g}E}bU0y>!WEc9 z@Vlnr7LMB|%GO5x&Sywc3fzsKwGAN{Ihr6&RhF1L#yk~_7qNFypbO(Z)(HZAaqg;u zKZxXA;+0VC5!K{ULg?b6f}8XucC->rFHk}|b1+zp-=sfDn3NjOZO=|n9_5BzYyX*A z^pl8a6WIXGiv+Z24C#*zcfn3L zjmee$098Wo78vE%%=PI>X=F7?D9pnCK1)k7xgzt;NQGR7@QE5A; z1wLMPKovGi^`uhv+XU%2o_)H-`ET)4qg7i>6C3)RvdI0S4jZ%p)j~Wn+KreGoIhy` zP~7-2zTg3f4vAgU3}J2mh>z>M8{ee%ntM=WCu01y#EEhSy%jxv-gHpe@6S1JDw3ve zAMN?`5%2|l$oo3NeqEdb^P{>E()qpj1@#|$+VHogSX7XLAOH^n^3DnZg7}X;?QHUo zLCvaf;%e)_=-}C@^JTx*g!jMl5M%q>+ystBcaXjkjDLb5ChCPCRUTGKFm#WM_Sf#-#+I?a1q8GIrHH95!pb$C@CdU zh)f92+cuJ0s+p-t8>uI=YsRw!q8P)8XMaI`?{h*=LJxy8Lk~SOu#DwT^HWdR+jxj$ zqe#rzVave>um*1MvtwX5vx0(}KpREdWRf5dAt?*aD%TU`<9{^NO7FY;G^-)7;`Mtj zFQQ*bXu`;Tu(ni1E)4(TSq7EU0inD1N0i)yIYP73NcO}?C8TMB zu#dT3@(>q-p}gH=;dys?en%FpK`d#s@*LEhNKIR>$qAZ2>&WM@6d~I+7tx!Ut3cKD z;(;}Uc3+*MDcOF8hdLw&;?5z&v4_1cTSgLF@GmA2pVl+QYN_O5SGjg8K*GNqMlPik z3B#n7(DzTz5o{7&zKR@s#J}!^nq&MIdw!eJ*oZLP)0q0Llsp*GD zvOqUJ7Hz7IhqteWs+!HtZtm7cCPf8+ryDcB>#a+yyUp)w=N=bWx;hxg8vNTl*vtf5 za^d>XJ?{KBCGL8|P#$f4=}H?EXf$)Q%cjBUZI;|Dj&92l^%|9CvMt1*sGmhhUCuCXl)Pa?&Oa76vpE9yONX+Vj0w^dHm; z#G9gble(N~HyNY|xQ@^(69t_}fAzL#=4brjO)8iO2rj{YoF{TA?Ssg~Zy|*|ha6JQq^Kk3a|u2=;wbuaYYc_^{76k? zSmaS=a?vdP$qezsq|`yN(Uspp!@j?r`&W?+n$sBIM5+W&Aab?o{GwdQps8Q$eV2W1 zlf{)n-XsIepb+x5c&QD&bwAh-4_zvEm90%-lzcP;sMW`U_PkqTd}N5Oks6?$AyWc}ewhPEFY`6Kc2%*y>D=AhbW(OSAYuMl zLUt5xK&IV`6E8%~*jJ2dVT=B8Rjx8({Vh#A4|hIe3mW?e-XfvbRDWheA?BUUBYRN( zrU5*tM3KE=9NdZgL~9znZ^Q!?EH0-?Es7u!$P~KY`#1^_W7>d zh!_WN3iy$UPZ zTZL9c`VI^dlA$%Ndvf8LXaVG6U-?35=!}bBvtE@sYcGQOs6iLhKZz`4Za$>A37D^OEk1h&1%Hc8BFRO;r~*A$ZQgu(%D382g|w3u$FUdx8Q zR79MHTy!_m-%3@}k|=69Wm!YqIVcHe7i_*Pum74sTq=WxS{$p>kT(|@BzDaqi6zjg zq}O}dj&Lx_thK}dA}S%Jth>n!-qI%A}Zh%oQ)c8_+^ve zGJ+-$G{au+`G-~N&>iMhp-qojbzvh1AqyyA;#0~7M-NN!V=Y#g912It8ra7(JH2_k zvHk+}gTl9+|1}$5bNOU!+HY-{TV#smxq~k6Lv0QV?S|_V|)|CeSgYnriZNVDnJ0zKI)*xtnDL-+h|32p=63~ZGcyRfpy789 zH5f)U28%UvThHqB*&3ltYXIwqxv*V%9)ZoNlDWq^>WBxks(5Ih_3O8R8-nLUn@&uP zQ#Z?7^(?-T(7*e|7yL_8ZuijR;}Io`ay?JiBlJ$gKp_jBtEahi!G%nNLg@%s@>+wSDVxQxDHqtveEdS{U2ZQ#7Em)Gi8tq3#Akz> z>66Xz(I&gB#ezVn)%WXjw-;LmpJm}nX$WIH@Op0q-05MoeJM)Za9V&$6=5C8zxU;O zpQu}C^i z1MMeVe^jf_?|qM0YamB8tJp^DPKBUJ?g1i^Dgy#*m7wFYGHaq@z%?b=%qHQ6VxV>w z(Pm}JwCkcbGXWm?kgqV)VH2q|q#WcrUypplV#5SkQ$@$Lk3{e##O`Gjm(b>E0U|Xc zuawoNH^N@c`Yg19IBeGc$lEg%QL$iS`5?sVnC3aJj9~ru0q_ipRy;eP=r_k-2;T8q z?ih4}5mD1Vk?V{sp2zBAW4RL(wiw=eJgN;l^Az+I?x!3>dUuDvHQBRc$(9E7 z_2q}maOfsOY`MHgp;Lr(>&C4ivLtmn-WFKQ{e2aq@Kr$SMd=TcW?4ZlF>R!o_7Xub zZd->OL=c^FOP_2#vnpcd$D$1#h>n#uS#z?jrt{S_ORB5Q+~=- zH3(4qB|x@6KfzSYB6mgi7w(MV^SwLw*cnef0;A^j&3X%BkK}&eC|WrKw`te~^__br&( zHmhQVoOfrRJ>-sCsiR_tNuCsTE$aN(Nq*q0k+Mh?j?sO&M%NPcUy9FtF1hP-amV<4 zU67i+RVD>-_`h+>*z%1V&h6I6c4-f)A$?4 zA^^E!=MM|0^mAz)WR|}SHp3m|eZ*@MJg|Ic##ofthm5xCk%pnIWJzxcRvm_$4@Zj4 zjZdhzX!D5&p5a$5i!E`#xq6;3Bz=GD;lWP(c*SYDC|c`*Z?`77P1zfP&6#^$f3t|n z36|hlUariyi?++(Q?~_Is^I&jbL^~ADF|pOLcP0&Cm}f0iA+6!9C^jp<8RYL@f3hg zjU+&|_WVAVB%U-|jn{TbA4TDL9BwJpdr5W3r;MG{ali28ljZV@s%{lBceA(}q+#lx zP`FLiaqgZxpIQHAeFdcd%&4%vC~AtWTXp5w%gg5<@rHUFIx2d zh+&_>NG5x0g`a&njhAmm1$qFgd6q%rZa*s(L3uotE&UUQ@Xy}TI3UV-qfq`S-EHgT z6qD^zzdt-373lPQ!vx@$pP z9Ru^nUPD=1Rg&xS*EVhM&lo@HpTDB|t=_}}ZF^M7Mm z{|)=!0@>kz6!O2*|AXWDC)V}9_40p%|6j!X4|bRAziFx@3jz6W5A2_+`1gOxe_#Ix DCnVIZ literal 10087 zcmaL7V{j!v*Zq6qi8b-WwoYu@b~3Ruv27bCwrx&qn-kl{1b3eIR^58)|K5A6t7~_E z=vCEK>&x2vrzisf`5gcNd;_41Ac~;1hZwjZ007J^000u;2f)e1#@?L8z{JJYfx*E; zO%)aZK`{rbEVu%z?BWg&0E2u40|5T#eYduc{RTVwSLf&Vs=&Ob3ipT&^VL98!Sy1Y z`jRQoLtoBNXx?aYwOR?Vo0Bcn=lM9cNHVfu(FC6YGInbJ!=0DlI%Mz9e(ia~%Nx6q zfl3ScYmK(K4KOmwMkJ7^rm`bXNH9?@2Lod)Dp+lHynv?9F6TIVDKiV;rFkIKYz;3Bf5Ch-qX|N?qkU9?pV<-K9z`#ZbF6`CW_Fi+w2FcLJukytO^TKNyog*Lu3Qj0$T}|*x*y#1#v+PKorgM^R zci~g&oh8_tM7z^CS6E7wz_-$h)(;mciFG37LA`wkS-0%~oJ8JYPK(q+;$$+}g^O5* zQbUwNC6r(`ItwsY5&3YpaT?7{tX*5Z8Ucz)2=0?cNd6PRL*XexdQnJf+{VsQX0v{FM`>qGo((^C9 zoQa$tpBp0biCrt#z`waxLtQ%8>Cw9jl=iIRlszR~JIPo`;~ei~`+Uj!kU$U-O)J>5papx6c~e1D-*AboN=+cARG*U2`IK;r z`dBCl>^h2Giz5tO-#;q$%LM2uImOFTF z15Tl2KU2flP8UMuZ0IQMfdE;xIr1Vx0MiW7vI=BEJUgqlMso3ED2~d;fTGyTPYxg; z9-6ci8j)y=qRNm|_k;7W;z9R>sv+M;G|o!!ry4r$uT&H-P`xgZOV7b+xMlJ3UHAt| z@7~zlQ}`x{vTAg);NzH{a`jkJEw8Y^Aqow%jTzZ6eJX`%$d+i6O(s1yy~SbG7)l%1 zU(w688v4u)Egv_do{)S*&dm!u;3+hy7QZUW@i9_CtH83k%?;#8{3Zc&kDCRzBRx1g z8yx@Iln4M4SsiA=;>rui0I&E5fR+6#r$DL_^wrW~&v_!&RXQ>ur zZ*mMrdrSxh;upU$c#_rI5yyqBBu`RsFqv_g8ZWI-DqQ98XN2c)Lp5Zyq1#n*GB$jB zmnCIsWFz9e7G?WsWp=9L6kZ)^m%WNtwFKj4zfVAXsAKLHu*%Dy!S-}J@U*lcw$6+0mql^qO1PMlw9WCzcc5TmM zFB76W{8^t4>+G*F8kc||q0jo!2o_r^p+}&&p&9+Knt1+gLJrI_$tJMo;Kh;$c|?RB69 zO@YF&0_P~_y{kw{t#mtt+WFgEw^QxQpj_{+?oPHH=-8Z6V0iG~kRkI>x3a zL{Mx}cWib{tDX{_YD`_MAgqCDbflvmIW#frWum#j6n0?2MR4AQ_+ZNU$vAfE5S590 zV7-e{p)gTEWpB9}*6+N>G7du#Gqvc>nj3kwn1VtpOdRuIqr0yVf#rTP*8ZkytGX0Z z!=}Art+{j;bJfYDpo4pfYudZd&p6Y1z6v>f=Je*3TK7w1G=j=O9>IdXn5Tlz!GCOY z6{>`>ekR}{AXS^b8)^Lw;iAPx$5xKPXT7B35;++&v7#;PvA@0IXIC>qOMOuF;-ElF z`q#s{mduj0M~7Xd57Rb*bk2KtE7$_)(CFcp4W-#$(Z;nLolzwp=}0x54^g`gg4~DE zo$Am_ZlV;tsmc5%OAK&qGL>+fQpe6z|HoyS@gI?i1;fz=_$(%g40`W7GP*)C50(sJ z>%_S3*ZgA!_ye50zRwHdi!%rHdVy=B+*A*cs_{%~{3hmA&dPS?^mgV@cknhTBWp{s zm?@IJsV%zgv=(YyH8%y(+gU3Fg{?|y%AwM&P%Umg>r$bsnkEL18!kSF@0_om3wnE! zuZXmy-hR)zAZ(Q|1$I;6=pF|AYsS^f8evZTvnp3CTxpe)w@3t|Xozy5i>6@y0D9&T zkkB{gISID5nRHt+Sd|=zqZx9|%)pg=zAOy@fJlGa6`UJ-$|Do z>BxN%eHD8r#_!`l5x=y5&u^jsRD=%~0Qoc;IFg>w-^;?I)cz6pt$IS*6iVrHUfjIK zpLZ6=>RO#oBdy00(Q(&?5!*9cH(Bu&Wvz7CqQL#p)27bGjnJd)h(UpL52WN_&o~IC z$Zj}s>eD=;d_l9?lvkFWdd}%>k99_D&_5qK;3s~_nMWv+LQb@pk5GhtJ0LNk3Vn4!u|;lO6lX*&?%l6pECcO_?=dSHVj38fimtMTIZ) z9$?i!LT6UI?Iv4+TA?zyZ`oBd5Grj>?ut$diMKdSiH)xYN?t7qkK0{)p4cCT!IQwa zDYZ)Zt9eI&>Xl9S_N%ewPskVEnRnh^6wP zngawH0)ad-_pK|_B7q5TPskoUP;2zi3TesJFl5LoYGjg?ub`>H@A!@ch1T)oZI4&b z{^jXm&zspibReOBvNGtht7Cg>n8262R@V*R%ad`)!pZ0M*Hzam=kt5}3QRvP%HqH~ zyq)mV&U1we66s7OV>cSLBJ{OLM-g}qEmHG7{6>!uB>85==vmiePnZF)pPooL!(>P> zmdXS}Qf<~05u?8$l$%*tgB-J4f&7--_i#o1W@nTsra>FLvd?6*Hxh>e=*R;MgSt95 zf=C4(ZIFoJSt_Ag>r3<_w=KmbpGAI4IaG&Fj5XLm8N(Dw6$&3g! zQBwnSZU+s`_$D3qg1S}_uOS=iV|+g~r*J6}OX9>QQ7Sz3^>gOVM~DBC$d z9^G%3Io;Wp+`a|I?QcO6#5Vuo)2#o)g39c{^B$CE!BG|+R4sy6^5_#d`@Q*R}%M;35W8W^=(wGmS9CpEpjc`pauEG-<_5ah)ED?Bp!olU7x91Lh0{ik zpBf7QFgF7LVE=`ef6>L*-p-Z5_J49q@c(;mx#Y99-;hk)hDraLZG;I?79R6ll_v@7 zvohhDtD(n9%#u~N#s-Q>Z7LSUA`3WreVsb=e*UgJgIOz*jF3P0fy8MUhi!t$9;R?$b$?bb*I>mPS|;jD%ymor?2LkH+B$W$ zcpJ<%-l+YZJbFkNW{#yX=xDeoi|pK1E3vcOf(OYY?RJxEC*aF!-fZ9(@QeJ;QGqaa z@bzY3>hRTp1l1-8=NM4S#MJpJcZwslsv}SR^>U|!`w5j zZ{88}_vg=5Xy0Ait(M#QM>*GagGFhR%}m+1Amsgz{^EE!3KVNT&4Os&j(mxCiLYrO z_)6s#$#41%GMNR4vEB)pi*i&blTv+qL*zp;SZh#c^u804*)%WLxP*@Tc<>c z3yT|H@8&(k&-J5mXK+VB!z!#D-8YdVU9=j7oQY+0m5k{NkmKPZf-G_w)7Zy6OR8=* zHldXXV3KKbX+2c`iPVZJ2ypgj0iCDTT55BKoMudaBb-!^n+_d#QrI@_qDw`%3~m31 zZn?(}MteUvxukN5Z5pVjCsWO?`E5n3j^O4wrgVF|N^e_u_cts)tznSa5eY8lt+4e& z#RwCMp?2tTtrT7eG%ILmwr zeq?F~j8|;4JHeGYbtSA!q)26k*qUyJQV!A|0W)Fl;bSjwcG+k!zB9pXVO4sX`UaW$ z5>BQH7CN51#9Q90qZX8~E2`lR<$`5~HN8%@Eo!^d2-5I|9T)7*1$!jOMfz|T3u?iN zM;98@wirL5dMszG5x!kLfcN)6T{$nl%6jH{7BVKq)dgH*y;EDPOa6|d!~EPbwOZTl zfJvoff-?O}ju?>eXD1n9W>lNJ`Nm3iT6_Th zuAbv8VOP+99bJD$$l`0ykrTw^_Rz$78s7lniVhTfiB91|2kYhD`N{LGQ!d>c`72-3 ziSUn;&~LqP=GLQug^C^_Vgh%f6y0!wu6`1 z)G-Cym3Ipwr?=-9*XHM!`LnC5M8J5-O5oJw`c)hk!k;n@oX5V{gj=lHGx)pmm23ow zzd7`vtDQXK4HMHdeofnlFdt`mXhZp|H=>#MKM>?@F&I=s4wy`>=g+ z42`nS4p=M_lRn?B%y8?Mtqe;Y+8@=CzKbv*of5u*jg!R)%!gxpi*QK97m2BxYf)0& zKb*wz;I?}Ne_M_Qe+4zX8oml~1?Hnc`6Ww-Jod*S2leG5OsZwPSR=EKd1z^gpumyr z%=q^lP0{IATc1nZl_q{sDrets`+rQX#svvPN>i&x0F7lqeasD}=`O+2mZ5k$kN!V|1c^&YLFmZk9*~uZ~`^pd z4@rMp=IHIuQsKaNtu#-!c)IyUj7DAEi>)<>kk(jbA-U_c^UKKHP&Gr+iiRiDERd-aq zh+P|5&?=vd1lEO5l}SL%lD@Ye#7PX^oYQtw>jBc-Z=_4(sXCe%|a5Z%X@_c`t~jZpY!8Khe=AhRrA} ztx`6GI;tYfd6Ax|U5%-O4AliIh7rMSS_~nWQ>}ubO_!*RxYc6svR_&7iPOS*W)rT{ z{sTocP^EJj(@gPCp1K-?;j%PaEh@@)!S@RWS(M>C-QGa)YG41P1XAB$`1cv0Lp|ML zd8wKflNxdLocgrDNtC1?R@gGMwVW( zv#~D9Jn7-T0$WdE1#5?-NtV=~N*Q^+xmWZQNqPky8P4;T^IgQw66Gt+JN8S?HP@lR z!u}C*GlG>z)s;bj=%uSps-m2MY8 z8mS}lGXRe!RTk&Sqq-(Ci@8+K@|j%V*I9Gx$iq44a=E zZRXBV%M80qLPqTLfy=5ZQV}Gfdm#%dE8|~I#D^GWrsN{OQ$nG^m zZEE`6?L*6KK{A+aiIt{keG)%dAC#ZmfoiNC*~vMOb>QlZa?@hOLoTZaCI~e2X?Q|q z8$a|@mh`}Asz+6%;na*;Wur}OO}=q%^wOZFY0z5C4#~S25o22u6r|HY*9*TLf9^QH zWB}I>1`gA8kw$#zu8Rj=&3;UWX+!eNSn8sbLMZ`SYL zn=Pl`fs}ErPIr&4@;z(QW38QB9-F?IV`BrCS-dt$_q#AGInEUOK(APurk7-s+4fGN zHr4><)@Vcq;2CoXVg_Qv`^v^FJ^V`Hc;hv^`vKVJU#=7#-n-r(2)r($PRC7jQEmlj z$R{q?gCXC1LXXw^)Kk+ls#xyf%%`&rFw{xuoHE^CSVM=tTUd4C!(g8lP_$ zFJG2gNt(vm76ED}n);19GcJq}s5LC@kB44z&p_k3#$47Ju_|NKVrqfCL#79(Jac)003n)Ho5FmCLLucf?$~yaQULXV?J$|;#>DWYy{&u;Rb!6rrStyGTf}a7Q z^5Rk1NzOB|+}6?OAVt|z#Ad*TiPImk|F51y=(vY|R zx4ksxT6MpP8$#i?wb|6e^>RJM=;nTftxj2fcz4tdXJ2kTErLqm3H>V|ai z4}S}`&C5B;yKTD4SCF)uhmH16Y)e`o<|Bz*nn5y?IO07&+{>X16>u4J_Up_bw?(+GRfjY;Xj`uoKS-D<5` z-L_GmuLRUze5{M-j=IsV1hJ#LdnjrV6t(I$qdFvrRgbTf&da^gs}bmuG6D8ew+ajmg4rk>39hFvuwM4 zt|j}Ornf`Sha${!v_32_{G@XjJ^xmi*x^dv_H^9G*LG-4sZRz`E3(*MJNED|o*nX0zN$Qs-T%wj8mXE&byq zMD8g+;Np{?)ouGtqQWP^JD*~KsG<&7Uv}WMb>vxaWeK6XPJ=T}IUV+=f&06!wXjS; z4i9DT=9-&=zXHp3y1%$uc`yzjY)9n#GvoruL$-4k>(jX}3AMKs#&WvqU8-2Q%%-yJ z;1^yIqe8%gEnd-YCCPD$v1;B#OX+^BjPPn;g&hG2U@G>Be#B8N+4}C#$GmIAx8?JEk|jlYP2*=hR+NO+=l=0vr=~!=)MWas;{X{(2!D>!x-DX zh9-EiLLq7~jzi|l^s|V0GJ-BEf7f7lBvBu3)@VefffTE|hUsHc{~$s^4WZmkCb_nS zAB-0BXf##|C3y(6xY#l9U0&}R^XE+Y8qX7j%V>PPC8LVz7PP#AlD1}4M0y54v|v<> z{Z}6CBBuP)i0kbes+#taHsP4ZbRm~_s*$X31U75CX*VjcjJO3O2eWn=3&y%H*5W)zUjYIcQx^7 z1YYh-y(2JsRXgW{21biscnn9&A|0WTBLq#?WiIp{OKbuXXp>ZS|?(zog175NCKj6hNK{q;Q5dP9?Fpevn3hD+iR`2!Klnfuz*MP{iSAXQ5-4S7^yCK^u?fO` zZzF$Aq9YA8TS}wNNcAh-SdPvnp`RGhJ9L9n!Pkwq?rDLGcfOrMa z`|{D(#~T|sHb8FhUH0SV!KqU;u0$O7?9qp9$6MFVG+gT54blp1MM)eQeGVFV&~Uz2 z>rS1?PU~M`WOS)o)bJ{0L$GViE0f{M|C}0{DYUKj{>(E-)+%NT5{=-26*ZQqd-X*5 z^pabY<$M{frMfE2q0na)f+6##B)~C@|C}jxW_$~ZnkIbVho8U9%KiFt`uTXAJvrk( zT-^2J&!-66wf|Jz$b07BM?F6WHhw=s+a!*?;yA9jP4D?bCtPQMpOf+QfcY&z32ye7 z;=*Ql9@z6{>w4dE?6IyJ)-A)i6vG~I_gC|&i*1Z2k;>SgBAGmRI|>}~^;kekOZXzY zEKYTPK8;b(KX!sZuMiu%BdAo>{+7HtD&%yxQv*L>%KiY|OXHlchZg)V&TL1oo3qKc z-C<%hX>Pw5GK|MTu6SiuPk)A^Ajt~Ks=!G&BgUjqPexIv+20ZHZ&z}w>~p_&7O)EO z1caB#HdXkPuX$ygOFYt;Fp_<$PZHL{eXgC_M-C51+D6VDnV-v&l)`;%PS96J*c62M z<9srzb=K0{yA?BBO>t>%O?kjyD`|5P@eRpwwE$J1fZt)6mH9#FUX+$85(?S#NwRlH z@y6MUs$z@VW*LJJNr@ppg(!Dterc@r(kUhs_6rriCudD#%^QO{JEUjauTH^y8eICb z6;AH88J_a&i;e83Zz1r#3lBDexLCCgWAe-;PH3y&!I2D*pu8E!?r=y^S8qp8*inR; zTzTc`19pHpT1Y3HkUGyV>a#rK7>b$-ziV$1LT~U+y;Rp^;@j~)np$i3!Vh>T#)eBF zW185bV8h%cr>&{hP~JKeCNeq?pp4`*2wz42K1X(F6n>GXQGM8jUVbVz{KXhvk{ir+@oGBgyzl+>}9XlZEtoo3hR6PsES$x z2jT_EH3IBNa6{OY$9A)v?=KPX)>WCCa$7gScMIL5ooD-ldDd$>j)yg0e;%;G6tV0| zcMcg(HR?fll5ETzda7@uI{j&swj^Ax$|eMZ>8i@ECJh_{jVdgvl|w-qv1moI7>JhF zX*Ku)ZOserygHlC%Y<1CtFR1jTYp}TGs4T+yZ}Rrw-SDB6u4u|BaV50EEe9i{?H;U ziHj|Z`?^-#@!wg)W~w&Ik5-$X87L^nuDZ>T=>om$`3ogC*nH7L5Ubj2DT(X`wA}-2 zn2K2(g&`f4GCyykS(XU>&a$2r1YDs@kGpdz6?pZ6DDM&@@ZJX0;Sqpd0ms=_TyHd1 zRb91(^(}JdsB{ylxj&?HH)V=L6Z!H)=6Uz0#WMe_Sf8@5Pbt?@RQ4H_&4#TvOu3RM)JP-W(sg zDW4d=z4ipO+`p zY00=CwTB`Ti@zpM^yNz_AK5{LwLR^|qgDL|KeD}D$J1r#9J0rkIJsD_Q6}`JVzrVpx?F1eg)3m zA&*Bp69#oz7;{xpIdZ}Kyk~N#WiM`-SC34mxkcqWvBArxV3%!-5Y>Kgie# zdN920HKh$PHt4-z!5ObncNxV_o$?)|?AQ?5HJ{3DYba@|K(SA!?MU}Y$@xlUXI2iF zec=!9S^B*7UG~eL9fd+YCGR?brr$){5FbzW1Tu5~@-d`vYbZrUTQ%Ugd z$BF-tn8O~yCZe4kSDgNmN73>$V8n_Fpl5z!5m|phF_BSLBE;i5D996k)xXYTHNh^T z`~oP-fPoW2{D1Lf*#EdQ0N|gC07U`+IsKos8PxwxoBbc8*?(*P@3GH+Yj*!5+5T$? x^iS?TL!kd3x&Q6#|CXaB`{(!n^7%i#|M>iW=|MsN=Q9xh*8RV#Pw}7I{{>mxP2T_j From d9031844da2ed4c085db57d9793ef1b5b1913c3e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 00:13:55 +0400 Subject: [PATCH 83/87] Unused includes removed --- src/modules/mc_att_control/mc_att_control_main.cpp | 2 -- src/modules/mc_pos_control/mc_pos_control_main.cpp | 2 -- .../position_estimator_inav/position_estimator_inav_main.c | 3 --- 3 files changed, 7 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 01902ed0cf..24226880ed 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -53,11 +53,9 @@ #include #include #include -#include #include #include #include -#include #include #include #include diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 25d34c872d..b06655385a 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -51,7 +51,6 @@ #include #include #include -#include #include #include #include @@ -68,7 +67,6 @@ #include #include #include -#include #include #include #include diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index bf4f7ae974..ad363efe06 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -42,14 +42,11 @@ #include #include #include -#include #include #include #include #include #include -#include -#include #include #include #include From 98ee73463f428b420d4aeb44af4a7a90d8d40e41 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:14:40 +0100 Subject: [PATCH 84/87] Removed obsolete ROMFS folder for removed logging build. The logging makefile was removed in 9a54c7c6. --- ROMFS/px4fmu_logging/init.d/rcS | 88 -------------------------- ROMFS/px4fmu_logging/logging/conv.zip | Bin 10087 -> 0 bytes 2 files changed, 88 deletions(-) delete mode 100644 ROMFS/px4fmu_logging/init.d/rcS delete mode 100644 ROMFS/px4fmu_logging/logging/conv.zip diff --git a/ROMFS/px4fmu_logging/init.d/rcS b/ROMFS/px4fmu_logging/init.d/rcS deleted file mode 100644 index 7b88567197..0000000000 --- a/ROMFS/px4fmu_logging/init.d/rcS +++ /dev/null @@ -1,88 +0,0 @@ -#!nsh -# -# PX4FMU startup script for logging purposes -# - -# -# 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 error -fi - -uorb start - -# -# Start sensor drivers here. -# - -ms5611 start -adc start - -# mag might be external -if hmc5883 start -then - echo "using HMC5883" -fi - -if mpu6000 start -then - echo "using MPU6000" -fi - -if l3gd20 start -then - echo "using L3GD20(H)" -fi - -if lsm303d start -then - set BOARD fmuv2 -else - set BOARD fmuv1 -fi - -# Start airspeed sensors -if meas_airspeed start -then - echo "using MEAS airspeed sensor" -else - if ets_airspeed start - then - echo "using ETS airspeed sensor (bus 3)" - else - if ets_airspeed start -b 1 - then - echo "Using ETS airspeed sensor (bus 1)" - fi - fi -fi - -# -# Start the sensor collection task. -# IMPORTANT: this also loads param offsets -# ALWAYS start this task before the -# preflight_check. -# -if sensors start -then - echo "SENSORS STARTED" -fi - -sdlog2 start -r 250 -e -b 16 - -if sercon -then - echo "[init] USB interface connected" - - # Try to get an USB console - nshterm /dev/ttyACM0 & -fi \ No newline at end of file diff --git a/ROMFS/px4fmu_logging/logging/conv.zip b/ROMFS/px4fmu_logging/logging/conv.zip deleted file mode 100644 index 7cb837e5666f51eca7ed803dfef4581f01bec1f3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 10087 zcmaL7V{j!v*Zq6qi8b-WwoYu@b~3Ruv27bCwrx&qn-kl{1b3eIR^58)|K5A6t7~_E z=vCEK>&x2vrzisf`5gcNd;_41Ac~;1hZwjZ007J^000u;2f)e1#@?L8z{JJYfx*E; zO%)aZK`{rbEVu%z?BWg&0E2u40|5T#eYduc{RTVwSLf&Vs=&Ob3ipT&^VL98!Sy1Y z`jRQoLtoBNXx?aYwOR?Vo0Bcn=lM9cNHVfu(FC6YGInbJ!=0DlI%Mz9e(ia~%Nx6q zfl3ScYmK(K4KOmwMkJ7^rm`bXNH9?@2Lod)Dp+lHynv?9F6TIVDKiV;rFkIKYz;3Bf5Ch-qX|N?qkU9?pV<-K9z`#ZbF6`CW_Fi+w2FcLJukytO^TKNyog*Lu3Qj0$T}|*x*y#1#v+PKorgM^R zci~g&oh8_tM7z^CS6E7wz_-$h)(;mciFG37LA`wkS-0%~oJ8JYPK(q+;$$+}g^O5* zQbUwNC6r(`ItwsY5&3YpaT?7{tX*5Z8Ucz)2=0?cNd6PRL*XexdQnJf+{VsQX0v{FM`>qGo((^C9 zoQa$tpBp0biCrt#z`waxLtQ%8>Cw9jl=iIRlszR~JIPo`;~ei~`+Uj!kU$U-O)J>5papx6c~e1D-*AboN=+cARG*U2`IK;r z`dBCl>^h2Giz5tO-#;q$%LM2uImOFTF z15Tl2KU2flP8UMuZ0IQMfdE;xIr1Vx0MiW7vI=BEJUgqlMso3ED2~d;fTGyTPYxg; z9-6ci8j)y=qRNm|_k;7W;z9R>sv+M;G|o!!ry4r$uT&H-P`xgZOV7b+xMlJ3UHAt| z@7~zlQ}`x{vTAg);NzH{a`jkJEw8Y^Aqow%jTzZ6eJX`%$d+i6O(s1yy~SbG7)l%1 zU(w688v4u)Egv_do{)S*&dm!u;3+hy7QZUW@i9_CtH83k%?;#8{3Zc&kDCRzBRx1g z8yx@Iln4M4SsiA=;>rui0I&E5fR+6#r$DL_^wrW~&v_!&RXQ>ur zZ*mMrdrSxh;upU$c#_rI5yyqBBu`RsFqv_g8ZWI-DqQ98XN2c)Lp5Zyq1#n*GB$jB zmnCIsWFz9e7G?WsWp=9L6kZ)^m%WNtwFKj4zfVAXsAKLHu*%Dy!S-}J@U*lcw$6+0mql^qO1PMlw9WCzcc5TmM zFB76W{8^t4>+G*F8kc||q0jo!2o_r^p+}&&p&9+Knt1+gLJrI_$tJMo;Kh;$c|?RB69 zO@YF&0_P~_y{kw{t#mtt+WFgEw^QxQpj_{+?oPHH=-8Z6V0iG~kRkI>x3a zL{Mx}cWib{tDX{_YD`_MAgqCDbflvmIW#frWum#j6n0?2MR4AQ_+ZNU$vAfE5S590 zV7-e{p)gTEWpB9}*6+N>G7du#Gqvc>nj3kwn1VtpOdRuIqr0yVf#rTP*8ZkytGX0Z z!=}Art+{j;bJfYDpo4pfYudZd&p6Y1z6v>f=Je*3TK7w1G=j=O9>IdXn5Tlz!GCOY z6{>`>ekR}{AXS^b8)^Lw;iAPx$5xKPXT7B35;++&v7#;PvA@0IXIC>qOMOuF;-ElF z`q#s{mduj0M~7Xd57Rb*bk2KtE7$_)(CFcp4W-#$(Z;nLolzwp=}0x54^g`gg4~DE zo$Am_ZlV;tsmc5%OAK&qGL>+fQpe6z|HoyS@gI?i1;fz=_$(%g40`W7GP*)C50(sJ z>%_S3*ZgA!_ye50zRwHdi!%rHdVy=B+*A*cs_{%~{3hmA&dPS?^mgV@cknhTBWp{s zm?@IJsV%zgv=(YyH8%y(+gU3Fg{?|y%AwM&P%Umg>r$bsnkEL18!kSF@0_om3wnE! zuZXmy-hR)zAZ(Q|1$I;6=pF|AYsS^f8evZTvnp3CTxpe)w@3t|Xozy5i>6@y0D9&T zkkB{gISID5nRHt+Sd|=zqZx9|%)pg=zAOy@fJlGa6`UJ-$|Do z>BxN%eHD8r#_!`l5x=y5&u^jsRD=%~0Qoc;IFg>w-^;?I)cz6pt$IS*6iVrHUfjIK zpLZ6=>RO#oBdy00(Q(&?5!*9cH(Bu&Wvz7CqQL#p)27bGjnJd)h(UpL52WN_&o~IC z$Zj}s>eD=;d_l9?lvkFWdd}%>k99_D&_5qK;3s~_nMWv+LQb@pk5GhtJ0LNk3Vn4!u|;lO6lX*&?%l6pECcO_?=dSHVj38fimtMTIZ) z9$?i!LT6UI?Iv4+TA?zyZ`oBd5Grj>?ut$diMKdSiH)xYN?t7qkK0{)p4cCT!IQwa zDYZ)Zt9eI&>Xl9S_N%ewPskVEnRnh^6wP zngawH0)ad-_pK|_B7q5TPskoUP;2zi3TesJFl5LoYGjg?ub`>H@A!@ch1T)oZI4&b z{^jXm&zspibReOBvNGtht7Cg>n8262R@V*R%ad`)!pZ0M*Hzam=kt5}3QRvP%HqH~ zyq)mV&U1we66s7OV>cSLBJ{OLM-g}qEmHG7{6>!uB>85==vmiePnZF)pPooL!(>P> zmdXS}Qf<~05u?8$l$%*tgB-J4f&7--_i#o1W@nTsra>FLvd?6*Hxh>e=*R;MgSt95 zf=C4(ZIFoJSt_Ag>r3<_w=KmbpGAI4IaG&Fj5XLm8N(Dw6$&3g! zQBwnSZU+s`_$D3qg1S}_uOS=iV|+g~r*J6}OX9>QQ7Sz3^>gOVM~DBC$d z9^G%3Io;Wp+`a|I?QcO6#5Vuo)2#o)g39c{^B$CE!BG|+R4sy6^5_#d`@Q*R}%M;35W8W^=(wGmS9CpEpjc`pauEG-<_5ah)ED?Bp!olU7x91Lh0{ik zpBf7QFgF7LVE=`ef6>L*-p-Z5_J49q@c(;mx#Y99-;hk)hDraLZG;I?79R6ll_v@7 zvohhDtD(n9%#u~N#s-Q>Z7LSUA`3WreVsb=e*UgJgIOz*jF3P0fy8MUhi!t$9;R?$b$?bb*I>mPS|;jD%ymor?2LkH+B$W$ zcpJ<%-l+YZJbFkNW{#yX=xDeoi|pK1E3vcOf(OYY?RJxEC*aF!-fZ9(@QeJ;QGqaa z@bzY3>hRTp1l1-8=NM4S#MJpJcZwslsv}SR^>U|!`w5j zZ{88}_vg=5Xy0Ait(M#QM>*GagGFhR%}m+1Amsgz{^EE!3KVNT&4Os&j(mxCiLYrO z_)6s#$#41%GMNR4vEB)pi*i&blTv+qL*zp;SZh#c^u804*)%WLxP*@Tc<>c z3yT|H@8&(k&-J5mXK+VB!z!#D-8YdVU9=j7oQY+0m5k{NkmKPZf-G_w)7Zy6OR8=* zHldXXV3KKbX+2c`iPVZJ2ypgj0iCDTT55BKoMudaBb-!^n+_d#QrI@_qDw`%3~m31 zZn?(}MteUvxukN5Z5pVjCsWO?`E5n3j^O4wrgVF|N^e_u_cts)tznSa5eY8lt+4e& z#RwCMp?2tTtrT7eG%ILmwr zeq?F~j8|;4JHeGYbtSA!q)26k*qUyJQV!A|0W)Fl;bSjwcG+k!zB9pXVO4sX`UaW$ z5>BQH7CN51#9Q90qZX8~E2`lR<$`5~HN8%@Eo!^d2-5I|9T)7*1$!jOMfz|T3u?iN zM;98@wirL5dMszG5x!kLfcN)6T{$nl%6jH{7BVKq)dgH*y;EDPOa6|d!~EPbwOZTl zfJvoff-?O}ju?>eXD1n9W>lNJ`Nm3iT6_Th zuAbv8VOP+99bJD$$l`0ykrTw^_Rz$78s7lniVhTfiB91|2kYhD`N{LGQ!d>c`72-3 ziSUn;&~LqP=GLQug^C^_Vgh%f6y0!wu6`1 z)G-Cym3Ipwr?=-9*XHM!`LnC5M8J5-O5oJw`c)hk!k;n@oX5V{gj=lHGx)pmm23ow zzd7`vtDQXK4HMHdeofnlFdt`mXhZp|H=>#MKM>?@F&I=s4wy`>=g+ z42`nS4p=M_lRn?B%y8?Mtqe;Y+8@=CzKbv*of5u*jg!R)%!gxpi*QK97m2BxYf)0& zKb*wz;I?}Ne_M_Qe+4zX8oml~1?Hnc`6Ww-Jod*S2leG5OsZwPSR=EKd1z^gpumyr z%=q^lP0{IATc1nZl_q{sDrets`+rQX#svvPN>i&x0F7lqeasD}=`O+2mZ5k$kN!V|1c^&YLFmZk9*~uZ~`^pd z4@rMp=IHIuQsKaNtu#-!c)IyUj7DAEi>)<>kk(jbA-U_c^UKKHP&Gr+iiRiDERd-aq zh+P|5&?=vd1lEO5l}SL%lD@Ye#7PX^oYQtw>jBc-Z=_4(sXCe%|a5Z%X@_c`t~jZpY!8Khe=AhRrA} ztx`6GI;tYfd6Ax|U5%-O4AliIh7rMSS_~nWQ>}ubO_!*RxYc6svR_&7iPOS*W)rT{ z{sTocP^EJj(@gPCp1K-?;j%PaEh@@)!S@RWS(M>C-QGa)YG41P1XAB$`1cv0Lp|ML zd8wKflNxdLocgrDNtC1?R@gGMwVW( zv#~D9Jn7-T0$WdE1#5?-NtV=~N*Q^+xmWZQNqPky8P4;T^IgQw66Gt+JN8S?HP@lR z!u}C*GlG>z)s;bj=%uSps-m2MY8 z8mS}lGXRe!RTk&Sqq-(Ci@8+K@|j%V*I9Gx$iq44a=E zZRXBV%M80qLPqTLfy=5ZQV}Gfdm#%dE8|~I#D^GWrsN{OQ$nG^m zZEE`6?L*6KK{A+aiIt{keG)%dAC#ZmfoiNC*~vMOb>QlZa?@hOLoTZaCI~e2X?Q|q z8$a|@mh`}Asz+6%;na*;Wur}OO}=q%^wOZFY0z5C4#~S25o22u6r|HY*9*TLf9^QH zWB}I>1`gA8kw$#zu8Rj=&3;UWX+!eNSn8sbLMZ`SYL zn=Pl`fs}ErPIr&4@;z(QW38QB9-F?IV`BrCS-dt$_q#AGInEUOK(APurk7-s+4fGN zHr4><)@Vcq;2CoXVg_Qv`^v^FJ^V`Hc;hv^`vKVJU#=7#-n-r(2)r($PRC7jQEmlj z$R{q?gCXC1LXXw^)Kk+ls#xyf%%`&rFw{xuoHE^CSVM=tTUd4C!(g8lP_$ zFJG2gNt(vm76ED}n);19GcJq}s5LC@kB44z&p_k3#$47Ju_|NKVrqfCL#79(Jac)003n)Ho5FmCLLucf?$~yaQULXV?J$|;#>DWYy{&u;Rb!6rrStyGTf}a7Q z^5Rk1NzOB|+}6?OAVt|z#Ad*TiPImk|F51y=(vY|R zx4ksxT6MpP8$#i?wb|6e^>RJM=;nTftxj2fcz4tdXJ2kTErLqm3H>V|ai z4}S}`&C5B;yKTD4SCF)uhmH16Y)e`o<|Bz*nn5y?IO07&+{>X16>u4J_Up_bw?(+GRfjY;Xj`uoKS-D<5` z-L_GmuLRUze5{M-j=IsV1hJ#LdnjrV6t(I$qdFvrRgbTf&da^gs}bmuG6D8ew+ajmg4rk>39hFvuwM4 zt|j}Ornf`Sha${!v_32_{G@XjJ^xmi*x^dv_H^9G*LG-4sZRz`E3(*MJNED|o*nX0zN$Qs-T%wj8mXE&byq zMD8g+;Np{?)ouGtqQWP^JD*~KsG<&7Uv}WMb>vxaWeK6XPJ=T}IUV+=f&06!wXjS; z4i9DT=9-&=zXHp3y1%$uc`yzjY)9n#GvoruL$-4k>(jX}3AMKs#&WvqU8-2Q%%-yJ z;1^yIqe8%gEnd-YCCPD$v1;B#OX+^BjPPn;g&hG2U@G>Be#B8N+4}C#$GmIAx8?JEk|jlYP2*=hR+NO+=l=0vr=~!=)MWas;{X{(2!D>!x-DX zh9-EiLLq7~jzi|l^s|V0GJ-BEf7f7lBvBu3)@VefffTE|hUsHc{~$s^4WZmkCb_nS zAB-0BXf##|C3y(6xY#l9U0&}R^XE+Y8qX7j%V>PPC8LVz7PP#AlD1}4M0y54v|v<> z{Z}6CBBuP)i0kbes+#taHsP4ZbRm~_s*$X31U75CX*VjcjJO3O2eWn=3&y%H*5W)zUjYIcQx^7 z1YYh-y(2JsRXgW{21biscnn9&A|0WTBLq#?WiIp{OKbuXXp>ZS|?(zog175NCKj6hNK{q;Q5dP9?Fpevn3hD+iR`2!Klnfuz*MP{iSAXQ5-4S7^yCK^u?fO` zZzF$Aq9YA8TS}wNNcAh-SdPvnp`RGhJ9L9n!Pkwq?rDLGcfOrMa z`|{D(#~T|sHb8FhUH0SV!KqU;u0$O7?9qp9$6MFVG+gT54blp1MM)eQeGVFV&~Uz2 z>rS1?PU~M`WOS)o)bJ{0L$GViE0f{M|C}0{DYUKj{>(E-)+%NT5{=-26*ZQqd-X*5 z^pabY<$M{frMfE2q0na)f+6##B)~C@|C}jxW_$~ZnkIbVho8U9%KiFt`uTXAJvrk( zT-^2J&!-66wf|Jz$b07BM?F6WHhw=s+a!*?;yA9jP4D?bCtPQMpOf+QfcY&z32ye7 z;=*Ql9@z6{>w4dE?6IyJ)-A)i6vG~I_gC|&i*1Z2k;>SgBAGmRI|>}~^;kekOZXzY zEKYTPK8;b(KX!sZuMiu%BdAo>{+7HtD&%yxQv*L>%KiY|OXHlchZg)V&TL1oo3qKc z-C<%hX>Pw5GK|MTu6SiuPk)A^Ajt~Ks=!G&BgUjqPexIv+20ZHZ&z}w>~p_&7O)EO z1caB#HdXkPuX$ygOFYt;Fp_<$PZHL{eXgC_M-C51+D6VDnV-v&l)`;%PS96J*c62M z<9srzb=K0{yA?BBO>t>%O?kjyD`|5P@eRpwwE$J1fZt)6mH9#FUX+$85(?S#NwRlH z@y6MUs$z@VW*LJJNr@ppg(!Dterc@r(kUhs_6rriCudD#%^QO{JEUjauTH^y8eICb z6;AH88J_a&i;e83Zz1r#3lBDexLCCgWAe-;PH3y&!I2D*pu8E!?r=y^S8qp8*inR; zTzTc`19pHpT1Y3HkUGyV>a#rK7>b$-ziV$1LT~U+y;Rp^;@j~)np$i3!Vh>T#)eBF zW185bV8h%cr>&{hP~JKeCNeq?pp4`*2wz42K1X(F6n>GXQGM8jUVbVz{KXhvk{ir+@oGBgyzl+>}9XlZEtoo3hR6PsES$x z2jT_EH3IBNa6{OY$9A)v?=KPX)>WCCa$7gScMIL5ooD-ldDd$>j)yg0e;%;G6tV0| zcMcg(HR?fll5ETzda7@uI{j&swj^Ax$|eMZ>8i@ECJh_{jVdgvl|w-qv1moI7>JhF zX*Ku)ZOserygHlC%Y<1CtFR1jTYp}TGs4T+yZ}Rrw-SDB6u4u|BaV50EEe9i{?H;U ziHj|Z`?^-#@!wg)W~w&Ik5-$X87L^nuDZ>T=>om$`3ogC*nH7L5Ubj2DT(X`wA}-2 zn2K2(g&`f4GCyykS(XU>&a$2r1YDs@kGpdz6?pZ6DDM&@@ZJX0;Sqpd0ms=_TyHd1 zRb91(^(}JdsB{ylxj&?HH)V=L6Z!H)=6Uz0#WMe_Sf8@5Pbt?@RQ4H_&4#TvOu3RM)JP-W(sg zDW4d=z4ipO+`p zY00=CwTB`Ti@zpM^yNz_AK5{LwLR^|qgDL|KeD}D$J1r#9J0rkIJsD_Q6}`JVzrVpx?F1eg)3m zA&*Bp69#oz7;{xpIdZ}Kyk~N#WiM`-SC34mxkcqWvBArxV3%!-5Y>Kgie# zdN920HKh$PHt4-z!5ObncNxV_o$?)|?AQ?5HJ{3DYba@|K(SA!?MU}Y$@xlUXI2iF zec=!9S^B*7UG~eL9fd+YCGR?brr$){5FbzW1Tu5~@-d`vYbZrUTQ%Ugd z$BF-tn8O~yCZe4kSDgNmN73>$V8n_Fpl5z!5m|phF_BSLBE;i5D996k)xXYTHNh^T z`~oP-fPoW2{D1Lf*#EdQ0N|gC07U`+IsKos8PxwxoBbc8*?(*P@3GH+Yj*!5+5T$? x^iS?TL!kd3x&Q6#|CXaB`{(!n^7%i#|M>iW=|MsN=Q9xh*8RV#Pw}7I{{>mxP2T_j From 1afa53a159ee247a1c57ca59912077c5076c3997 Mon Sep 17 00:00:00 2001 From: Stefan Rado Date: Mon, 17 Feb 2014 21:15:35 +0100 Subject: [PATCH 85/87] Cleanup: Moved sdlog2 file conversion scripts to separate folder. --- Tools/{ => sdlog2}/README.txt | 0 Tools/{ => sdlog2}/logconv.m | 1070 ++++++++++++++--------------- Tools/{ => sdlog2}/sdlog2_dump.py | 0 3 files changed, 535 insertions(+), 535 deletions(-) rename Tools/{ => sdlog2}/README.txt (100%) rename Tools/{ => sdlog2}/logconv.m (97%) rename Tools/{ => sdlog2}/sdlog2_dump.py (100%) diff --git a/Tools/README.txt b/Tools/sdlog2/README.txt similarity index 100% rename from Tools/README.txt rename to Tools/sdlog2/README.txt diff --git a/Tools/logconv.m b/Tools/sdlog2/logconv.m similarity index 97% rename from Tools/logconv.m rename to Tools/sdlog2/logconv.m index c416b8095e..e19c97fa3c 100644 --- a/Tools/logconv.m +++ b/Tools/sdlog2/logconv.m @@ -1,535 +1,535 @@ -% This Matlab Script can be used to import the binary logged values of the -% PX4FMU into data that can be plotted and analyzed. - -%% ************************************************************************ -% PX4LOG_PLOTSCRIPT: Main function -% ************************************************************************ -function PX4Log_Plotscript - -% Clear everything -clc -clear all -close all - -% ************************************************************************ -% SETTINGS -% ************************************************************************ - -% Set the path to your sysvector.bin file here -filePath = 'log001.bin'; - -% Set the minimum and maximum times to plot here [in seconds] -mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] -maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] - -%Determine which data to plot. Not completely implemented yet. -bDisplayGPS=true; - -%conversion factors -fconv_gpsalt=1; %[mm] to [m] -fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] -fconv_timestamp=1E-6; % [microseconds] to [seconds] - -% ************************************************************************ -% Import the PX4 logs -% ************************************************************************ -ImportPX4LogData(); - -%Translate min and max plot times to indices -time=double(sysvector.TIME_StartTime) .*fconv_timestamp; -mintime_log=time(1); %The minimum time/timestamp found in the log -maxtime_log=time(end); %The maximum time/timestamp found in the log -CurTime=mintime_log; %The current time at which to draw the aircraft position - -[imintime,imaxtime]=FindMinMaxTimeIndices(); - -% ************************************************************************ -% PLOT & GUI SETUP -% ************************************************************************ -NrFigures=5; -NrAxes=10; -h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively -h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively -h.pathpoints=[]; % Temporary initiliazation of path points - -% Setup the GUI to control the plots -InitControlGUI(); -% Setup the plotting-GUI (figures, axes) itself. -InitPlotGUI(); - -% ************************************************************************ -% DRAW EVERYTHING -% ************************************************************************ -DrawRawData(); -DrawCurrentAircraftState(); - -%% ************************************************************************ -% *** END OF MAIN SCRIPT *** -% NESTED FUNCTION DEFINTIONS FROM HERE ON -% ************************************************************************ - - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -%% ************************************************************************ -% IMPORTPX4LOGDATA (nested function) -% ************************************************************************ -% Attention: This is the import routine for firmware from ca. 03/2013. -% Other firmware versions might require different import -% routines. - -function ImportPX4LogData() - - % ************************************************************************ - % RETRIEVE SYSTEM VECTOR - % ************************************************************************* - % //All measurements in NED frame - - % Convert to CSV - %arg1 = 'log-fx61-20130721-2.bin'; - arg1 = filePath; - delim = ','; - time_field = 'TIME'; - data_file = 'data.csv'; - csv_null = ''; - - if not(exist(data_file, 'file')) - s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); - end - - if exist(data_file, 'file') - - %data = csvread(data_file); - sysvector = tdfread(data_file, ','); - - % shot the flight time - time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); - time_s = uint64(time_us*1e-6); - time_m = uint64(time_s/60); - time_s = time_s - time_m * 60; - - disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); - - disp(['logfile conversion finished.' char(10)]); - else - disp(['file: ' data_file ' does not exist' char(10)]); - end -end - -%% ************************************************************************ -% INITCONTROLGUI (nested function) -% ************************************************************************ -%Setup central control GUI components to control current time where data is shown -function InitControlGUI() - %********************************************************************** - % GUI size definitions - %********************************************************************** - dxy=5; %margins - %Panel: Plotctrl - dlabels=120; - dsliders=200; - dedits=80; - hslider=20; - - hpanel1=40; %panel1 - hpanel2=220;%panel2 - hpanel3=3*hslider+4*dxy+3*dxy;%panel3. - - width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width - height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height - - %********************************************************************** - % Create GUI - %********************************************************************** - h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); - h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); - h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); - h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); - - %%Control GUI-elements - %Slider: Current time - h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... - 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); - temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); - set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); - h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... - 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); - - %Slider: MaxTime - h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %Slider: MinTime - h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); - h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... - 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... - 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); - - %%Current data/state GUI-elements (Multiline-edit-box) - h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... - 'HorizontalAlignment','left','parent',h.aircraftstatepanel); - - h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... - 'HorizontalAlignment','left','parent',h.guistatepanel); - -end - -%% ************************************************************************ -% INITPLOTGUI (nested function) -% ************************************************************************ -function InitPlotGUI() - - % Setup handles to lines and text - h.markertext=[]; - templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array - h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively - h.markerline(1:NrAxes)=0.0; - - % Setup all other figures and axes for plotting - % PLOT WINDOW 1: GPS POSITION - h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); - h.axes(1)=axes(); - set(h.axes(1),'Parent',h.figures(2)); - - % PLOT WINDOW 2: IMU, baro altitude - h.figures(3)=figure('Name', 'IMU / Baro Altitude'); - h.axes(2)=subplot(4,1,1); - h.axes(3)=subplot(4,1,2); - h.axes(4)=subplot(4,1,3); - h.axes(5)=subplot(4,1,4); - set(h.axes(2:5),'Parent',h.figures(3)); - - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); - h.axes(6)=subplot(4,1,1); - h.axes(7)=subplot(4,1,2); - h.axes(8)=subplot(4,1,3); - h.axes(9)=subplot(4,1,4); - set(h.axes(6:9),'Parent',h.figures(4)); - - % PLOT WINDOW 4: LOG STATS - h.figures(5) = figure('Name', 'Log Statistics'); - h.axes(10)=subplot(1,1,1); - set(h.axes(10:10),'Parent',h.figures(5)); - -end - -%% ************************************************************************ -% DRAWRAWDATA (nested function) -% ************************************************************************ -%Draws the raw data from the sysvector, but does not add any -%marker-lines or so -function DrawRawData() - % ************************************************************************ - % PLOT WINDOW 1: GPS POSITION & GUI - % ************************************************************************ - figure(h.figures(2)); - % Only plot GPS data if available - if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) - %Draw data - plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); - title(h.axes(1),'GPS Position Data(if available)'); - xlabel(h.axes(1),'Latitude [deg]'); - ylabel(h.axes(1),'Longitude [deg]'); - zlabel(h.axes(1),'Altitude above MSL [m]'); - grid on - - %Reset path - h.pathpoints=0; - end - - % ************************************************************************ - % PLOT WINDOW 2: IMU, baro altitude - % ************************************************************************ - figure(h.figures(3)); - plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); - title(h.axes(2),'Magnetometers [Gauss]'); - legend(h.axes(2),'x','y','z'); - plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); - title(h.axes(3),'Accelerometers [m/s²]'); - legend(h.axes(3),'x','y','z'); - plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); - title(h.axes(4),'Gyroscopes [rad/s]'); - legend(h.axes(4),'x','y','z'); - plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); - if(bDisplayGPS) - hold on; - plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); - hold off - legend('Barometric Altitude [m]','GPS Altitude [m]'); - else - legend('Barometric Altitude [m]'); - end - title(h.axes(5),'Altitude above MSL [m]'); - - % ************************************************************************ - % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... - % ************************************************************************ - figure(h.figures(4)); - %Attitude Estimate - plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); - title(h.axes(6),'Estimated attitude [deg]'); - legend(h.axes(6),'roll','pitch','yaw'); - %Actuator Controls - plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); - title(h.axes(7),'Actuator control [-]'); - legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); - %Actuator Controls - plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); - title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); - legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); - set(h.axes(8), 'YLim',[800 2200]); - %Airspeeds - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); - hold on - plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); - hold off - %add GPS total airspeed here - title(h.axes(9),'Airspeed [m/s]'); - legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); - %calculate time differences and plot them - intervals = zeros(0,imaxtime - imintime); - for k = imintime+1:imaxtime - intervals(k) = time(k) - time(k-1); - end - plot(h.axes(10), time(imintime:imaxtime), intervals); - - %Set same timescale for all plots - for i=2:NrAxes - set(h.axes(i),'XLim',[mintime maxtime]); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% DRAWCURRENTAIRCRAFTSTATE(nested function) -% ************************************************************************ -function DrawCurrentAircraftState() - %find current data index - i=find(time>=CurTime,1,'first'); - - %********************************************************************** - % Current aircraft state label update - %********************************************************************** - acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... - 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... - 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... - ', y=',num2str(sysvector.IMU_MagY(i)),... - ', z=',num2str(sysvector.IMU_MagZ(i)),']']; - acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... - ', y=',num2str(sysvector.IMU_AccY(i)),... - ', z=',num2str(sysvector.IMU_AccZ(i)),']']; - acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... - ', y=',num2str(sysvector.IMU_GyroY(i)),... - ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; - acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; - acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... - ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... - ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; - acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); - %for j=1:4 - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; - acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; - %end - acstate{7,:}=[acstate{7,:},']']; - acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); - %for j=1:8 - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; - acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; - %end - acstate{8,:}=[acstate{8,:},']']; - acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; - - set(h.edits.AircraftState,'String',acstate); - - %********************************************************************** - % GPS Plot Update - %********************************************************************** - %Plot traveled path, and and time. - figure(h.figures(2)); - hold on; - if(CurTime>mintime+1) %the +1 is only a small bugfix - h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... - double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); - end; - hold off - %Plot current position - newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; - if(numel(h.pathpoints)<=3) %empty path - h.pathpoints(1,1:3)=newpoint; - else %Not empty, append new point - h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; - end - axes(h.axes(1)); - line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); - - - % Plot current time (small label next to current gps position) - textdesc=strcat(' t=',num2str(time(i)),'s'); - if(isvalidhandle(h.markertext)) - delete(h.markertext); %delete old text - end - h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... - double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); - set(h.edits.CurTime,'String',CurTime); - - %********************************************************************** - % Plot the lines showing the current time in the 2-d plots - %********************************************************************** - for i=2:NrAxes - if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end - ylims=get(h.axes(i),'YLim'); - h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); - set(h.markerline(i),'parent',h.axes(i)); - end - - set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); -end - -%% ************************************************************************ -% MINMAXTIME CALLBACK (nested function) -% ************************************************************************ -function minmaxtime_callback(hObj,event) %#ok - new_mintime=get(h.sliders.MinTime,'Value'); - new_maxtime=get(h.sliders.MaxTime,'Value'); - - %Safety checks: - bErr=false; - %1: mintime must be < maxtime - if((new_mintime>maxtime) || (new_maxtimeCurTime) - set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); - mintime=new_mintime; - CurTime=mintime; - bErr=true; - end - %3: MaxTime must be >CurTime - if(new_maxtime - %find current time - if(hObj==h.sliders.CurTime) - CurTime=get(h.sliders.CurTime,'Value'); - elseif (hObj==h.edits.CurTime) - temp=str2num(get(h.edits.CurTime,'String')); - if(tempmintime) - CurTime=temp; - else - %Error - set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); - end - else - %Error - set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); - end - - set(h.sliders.CurTime,'Value',CurTime); - set(h.edits.CurTime,'String',num2str(CurTime)); - - %Redraw time markers, but don't have to redraw the whole raw data - DrawCurrentAircraftState(); -end - -%% ************************************************************************ -% FINDMINMAXINDICES (nested function) -% ************************************************************************ -function [idxmin,idxmax] = FindMinMaxTimeIndices() - for i=1:size(sysvector.TIME_StartTime,1) - if time(i)>=mintime; idxmin=i; break; end - end - for i=1:size(sysvector.TIME_StartTime,1) - if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end - if time(i)>=maxtime; idxmax=i; break; end - end - mintime=time(idxmin); - maxtime=time(idxmax); -end - -%% ************************************************************************ -% ISVALIDHANDLE (nested function) -% ************************************************************************ -function isvalid = isvalidhandle(handle) - if(exist(varname(handle))>0 && length(ishandle(handle))>0) - if(ishandle(handle)>0) - if(handle>0.0) - isvalid=true; - return; - end - end - end - isvalid=false; -end - -%% ************************************************************************ -% JUST SOME SMALL HELPER FUNCTIONS (nested function) -% ************************************************************************ -function out = varname(var) - out = inputname(1); -end - -%This is the end of the matlab file / the main function -end +% This Matlab Script can be used to import the binary logged values of the +% PX4FMU into data that can be plotted and analyzed. + +%% ************************************************************************ +% PX4LOG_PLOTSCRIPT: Main function +% ************************************************************************ +function PX4Log_Plotscript + +% Clear everything +clc +clear all +close all + +% ************************************************************************ +% SETTINGS +% ************************************************************************ + +% Set the path to your sysvector.bin file here +filePath = 'log001.bin'; + +% Set the minimum and maximum times to plot here [in seconds] +mintime=0; %The minimum time/timestamp to display, as set by the user [0 for first element / start] +maxtime=0; %The maximum time/timestamp to display, as set by the user [0 for last element / end] + +%Determine which data to plot. Not completely implemented yet. +bDisplayGPS=true; + +%conversion factors +fconv_gpsalt=1; %[mm] to [m] +fconv_gpslatlong=1; %[gps_raw_position_unit] to [deg] +fconv_timestamp=1E-6; % [microseconds] to [seconds] + +% ************************************************************************ +% Import the PX4 logs +% ************************************************************************ +ImportPX4LogData(); + +%Translate min and max plot times to indices +time=double(sysvector.TIME_StartTime) .*fconv_timestamp; +mintime_log=time(1); %The minimum time/timestamp found in the log +maxtime_log=time(end); %The maximum time/timestamp found in the log +CurTime=mintime_log; %The current time at which to draw the aircraft position + +[imintime,imaxtime]=FindMinMaxTimeIndices(); + +% ************************************************************************ +% PLOT & GUI SETUP +% ************************************************************************ +NrFigures=5; +NrAxes=10; +h.figures(1:NrFigures)=0.0; % Temporary initialization of figure handle array - these are numbered consecutively +h.axes(1:NrAxes)=0.0; % Temporary initialization of axes handle array - these are numbered consecutively +h.pathpoints=[]; % Temporary initiliazation of path points + +% Setup the GUI to control the plots +InitControlGUI(); +% Setup the plotting-GUI (figures, axes) itself. +InitPlotGUI(); + +% ************************************************************************ +% DRAW EVERYTHING +% ************************************************************************ +DrawRawData(); +DrawCurrentAircraftState(); + +%% ************************************************************************ +% *** END OF MAIN SCRIPT *** +% NESTED FUNCTION DEFINTIONS FROM HERE ON +% ************************************************************************ + + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +%% ************************************************************************ +% IMPORTPX4LOGDATA (nested function) +% ************************************************************************ +% Attention: This is the import routine for firmware from ca. 03/2013. +% Other firmware versions might require different import +% routines. + +function ImportPX4LogData() + + % ************************************************************************ + % RETRIEVE SYSTEM VECTOR + % ************************************************************************* + % //All measurements in NED frame + + % Convert to CSV + %arg1 = 'log-fx61-20130721-2.bin'; + arg1 = filePath; + delim = ','; + time_field = 'TIME'; + data_file = 'data.csv'; + csv_null = ''; + + if not(exist(data_file, 'file')) + s = system( sprintf('python sdlog2_dump.py "%s" -f "%s" -t"%s" -d"%s" -n"%s"', arg1, data_file, time_field, delim, csv_null) ); + end + + if exist(data_file, 'file') + + %data = csvread(data_file); + sysvector = tdfread(data_file, ','); + + % shot the flight time + time_us = sysvector.TIME_StartTime(end) - sysvector.TIME_StartTime(1); + time_s = uint64(time_us*1e-6); + time_m = uint64(time_s/60); + time_s = time_s - time_m * 60; + + disp([sprintf('Flight log duration: %d:%d (minutes:seconds)', time_m, time_s) char(10)]); + + disp(['logfile conversion finished.' char(10)]); + else + disp(['file: ' data_file ' does not exist' char(10)]); + end +end + +%% ************************************************************************ +% INITCONTROLGUI (nested function) +% ************************************************************************ +%Setup central control GUI components to control current time where data is shown +function InitControlGUI() + %********************************************************************** + % GUI size definitions + %********************************************************************** + dxy=5; %margins + %Panel: Plotctrl + dlabels=120; + dsliders=200; + dedits=80; + hslider=20; + + hpanel1=40; %panel1 + hpanel2=220;%panel2 + hpanel3=3*hslider+4*dxy+3*dxy;%panel3. + + width=dlabels+dsliders+dedits+4*dxy+2*dxy; %figure width + height=hpanel1+hpanel2+hpanel3+4*dxy; %figure height + + %********************************************************************** + % Create GUI + %********************************************************************** + h.figures(1)=figure('Units','pixels','position',[200 200 width height],'Name','Control GUI'); + h.guistatepanel=uipanel('Title','Current GUI state','Units','pixels','Position',[dxy dxy width-2*dxy hpanel1],'parent',h.figures(1)); + h.aircraftstatepanel=uipanel('Title','Current aircraft state','Units','pixels','Position',[dxy hpanel1+2*dxy width-2*dxy hpanel2],'parent',h.figures(1)); + h.plotctrlpanel=uipanel('Title','Plot Control','Units','pixels','Position',[dxy hpanel1+hpanel2+3*dxy width-2*dxy hpanel3],'parent',h.figures(1)); + + %%Control GUI-elements + %Slider: Current time + h.labels.CurTime=uicontrol(gcf,'style','text','Position',[dxy dxy dlabels hslider],'String','Current time t[s]:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.CurTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels dxy dsliders hslider],... + 'min',mintime,'max',maxtime,'value',mintime,'callback',@curtime_callback,'parent',h.plotctrlpanel); + temp=get(h.sliders.CurTime,'Max')-get(h.sliders.CurTime,'Min'); + set(h.sliders.CurTime,'SliderStep',[1.0/temp 5.0/temp]); + h.edits.CurTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders dxy dedits hslider],'String',get(h.sliders.CurTime,'value'),... + 'BackgroundColor','white','callback',@curtime_callback,'parent',h.plotctrlpanel); + + %Slider: MaxTime + h.labels.MaxTime=uicontrol(gcf,'style','text','position',[dxy 2*dxy+hslider dlabels hslider],'String','Max. time t[s] to display:','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MaxTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 2*dxy+hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',maxtime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MaxTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 2*dxy+hslider dedits hslider],'String',get(h.sliders.MaxTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %Slider: MinTime + h.labels.MinTime=uicontrol(gcf,'style','text','position',[dxy 3*dxy+2*hslider dlabels hslider],'String','Min. time t[s] to dispay :','parent',h.plotctrlpanel,'HorizontalAlignment','left'); + h.sliders.MinTime=uicontrol(gcf,'style','slider','units','pix','position',[2*dxy+dlabels 3*dxy+2*hslider dsliders hslider],... + 'min',mintime_log,'max',maxtime_log,'value',mintime,'callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + h.edits.MinTime=uicontrol(gcf,'style','edit','position',[3*dxy+dlabels+dsliders 3*dxy+2*hslider dedits hslider],'String',get(h.sliders.MinTime,'value'),... + 'BackgroundColor','white','callback',@minmaxtime_callback,'parent',h.plotctrlpanel); + + %%Current data/state GUI-elements (Multiline-edit-box) + h.edits.AircraftState=uicontrol(gcf,'style','edit','Units','normalized','position',[.02 .02 0.96 0.96],'Min',1,'Max',10,'String','This shows the current aircraft state',... + 'HorizontalAlignment','left','parent',h.aircraftstatepanel); + + h.labels.GUIState=uicontrol(gcf,'style','text','Units','pixels','position',[dxy dxy width-4*dxy hslider],'String','Current state of this GUI',... + 'HorizontalAlignment','left','parent',h.guistatepanel); + +end + +%% ************************************************************************ +% INITPLOTGUI (nested function) +% ************************************************************************ +function InitPlotGUI() + + % Setup handles to lines and text + h.markertext=[]; + templinehandle=0.0;%line([0 1],[0 5]); % Just a temporary handle to init array + h.markerline(1:NrAxes)=templinehandle; % the actual handle-array to the lines - these are numbered consecutively + h.markerline(1:NrAxes)=0.0; + + % Setup all other figures and axes for plotting + % PLOT WINDOW 1: GPS POSITION + h.figures(2)=figure('units','normalized','Toolbar','figure', 'Name', 'GPS Position'); + h.axes(1)=axes(); + set(h.axes(1),'Parent',h.figures(2)); + + % PLOT WINDOW 2: IMU, baro altitude + h.figures(3)=figure('Name', 'IMU / Baro Altitude'); + h.axes(2)=subplot(4,1,1); + h.axes(3)=subplot(4,1,2); + h.axes(4)=subplot(4,1,3); + h.axes(5)=subplot(4,1,4); + set(h.axes(2:5),'Parent',h.figures(3)); + + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + h.figures(4)=figure('Name', 'Attitude Estimate / Actuators / Airspeeds'); + h.axes(6)=subplot(4,1,1); + h.axes(7)=subplot(4,1,2); + h.axes(8)=subplot(4,1,3); + h.axes(9)=subplot(4,1,4); + set(h.axes(6:9),'Parent',h.figures(4)); + + % PLOT WINDOW 4: LOG STATS + h.figures(5) = figure('Name', 'Log Statistics'); + h.axes(10)=subplot(1,1,1); + set(h.axes(10:10),'Parent',h.figures(5)); + +end + +%% ************************************************************************ +% DRAWRAWDATA (nested function) +% ************************************************************************ +%Draws the raw data from the sysvector, but does not add any +%marker-lines or so +function DrawRawData() + % ************************************************************************ + % PLOT WINDOW 1: GPS POSITION & GUI + % ************************************************************************ + figure(h.figures(2)); + % Only plot GPS data if available + if (sum(double(sysvector.GPS_Lat(imintime:imaxtime)))>0) && (bDisplayGPS) + %Draw data + plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:imaxtime))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:imaxtime))*fconv_gpsalt,'r.'); + title(h.axes(1),'GPS Position Data(if available)'); + xlabel(h.axes(1),'Latitude [deg]'); + ylabel(h.axes(1),'Longitude [deg]'); + zlabel(h.axes(1),'Altitude above MSL [m]'); + grid on + + %Reset path + h.pathpoints=0; + end + + % ************************************************************************ + % PLOT WINDOW 2: IMU, baro altitude + % ************************************************************************ + figure(h.figures(3)); + plot(h.axes(2),time(imintime:imaxtime),[sysvector.IMU_MagX(imintime:imaxtime), sysvector.IMU_MagY(imintime:imaxtime), sysvector.IMU_MagZ(imintime:imaxtime)]); + title(h.axes(2),'Magnetometers [Gauss]'); + legend(h.axes(2),'x','y','z'); + plot(h.axes(3),time(imintime:imaxtime),[sysvector.IMU_AccX(imintime:imaxtime), sysvector.IMU_AccY(imintime:imaxtime), sysvector.IMU_AccZ(imintime:imaxtime)]); + title(h.axes(3),'Accelerometers [m/s²]'); + legend(h.axes(3),'x','y','z'); + plot(h.axes(4),time(imintime:imaxtime),[sysvector.IMU_GyroX(imintime:imaxtime), sysvector.IMU_GyroY(imintime:imaxtime), sysvector.IMU_GyroZ(imintime:imaxtime)]); + title(h.axes(4),'Gyroscopes [rad/s]'); + legend(h.axes(4),'x','y','z'); + plot(h.axes(5),time(imintime:imaxtime),sysvector.SENS_BaroAlt(imintime:imaxtime),'color','blue'); + if(bDisplayGPS) + hold on; + plot(h.axes(5),time(imintime:imaxtime),double(sysvector.GPS_Alt(imintime:imaxtime)).*fconv_gpsalt,'color','red'); + hold off + legend('Barometric Altitude [m]','GPS Altitude [m]'); + else + legend('Barometric Altitude [m]'); + end + title(h.axes(5),'Altitude above MSL [m]'); + + % ************************************************************************ + % PLOT WINDOW 3: ATTITUDE ESTIMATE, ACTUATORS/CONTROLS, AIRSPEEDS,... + % ************************************************************************ + figure(h.figures(4)); + %Attitude Estimate + plot(h.axes(6),time(imintime:imaxtime), [sysvector.ATT_Roll(imintime:imaxtime), sysvector.ATT_Pitch(imintime:imaxtime), sysvector.ATT_Yaw(imintime:imaxtime)] .*180./3.14159); + title(h.axes(6),'Estimated attitude [deg]'); + legend(h.axes(6),'roll','pitch','yaw'); + %Actuator Controls + plot(h.axes(7),time(imintime:imaxtime), [sysvector.ATTC_Roll(imintime:imaxtime), sysvector.ATTC_Pitch(imintime:imaxtime), sysvector.ATTC_Yaw(imintime:imaxtime), sysvector.ATTC_Thrust(imintime:imaxtime)]); + title(h.axes(7),'Actuator control [-]'); + legend(h.axes(7),'ATT CTRL Roll [-1..+1]','ATT CTRL Pitch [-1..+1]','ATT CTRL Yaw [-1..+1]','ATT CTRL Thrust [0..+1]'); + %Actuator Controls + plot(h.axes(8),time(imintime:imaxtime), [sysvector.OUT0_Out0(imintime:imaxtime), sysvector.OUT0_Out1(imintime:imaxtime), sysvector.OUT0_Out2(imintime:imaxtime), sysvector.OUT0_Out3(imintime:imaxtime), sysvector.OUT0_Out4(imintime:imaxtime), sysvector.OUT0_Out5(imintime:imaxtime), sysvector.OUT0_Out6(imintime:imaxtime), sysvector.OUT0_Out7(imintime:imaxtime)]); + title(h.axes(8),'Actuator PWM (raw-)outputs [µs]'); + legend(h.axes(8),'CH1','CH2','CH3','CH4','CH5','CH6','CH7','CH8'); + set(h.axes(8), 'YLim',[800 2200]); + %Airspeeds + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_IndSpeed(imintime:imaxtime)); + hold on + plot(h.axes(9),time(imintime:imaxtime), sysvector.AIRS_TrueSpeed(imintime:imaxtime)); + hold off + %add GPS total airspeed here + title(h.axes(9),'Airspeed [m/s]'); + legend(h.axes(9),'Indicated Airspeed (IAS)','True Airspeed (TAS)','GPS Airspeed'); + %calculate time differences and plot them + intervals = zeros(0,imaxtime - imintime); + for k = imintime+1:imaxtime + intervals(k) = time(k) - time(k-1); + end + plot(h.axes(10), time(imintime:imaxtime), intervals); + + %Set same timescale for all plots + for i=2:NrAxes + set(h.axes(i),'XLim',[mintime maxtime]); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% DRAWCURRENTAIRCRAFTSTATE(nested function) +% ************************************************************************ +function DrawCurrentAircraftState() + %find current data index + i=find(time>=CurTime,1,'first'); + + %********************************************************************** + % Current aircraft state label update + %********************************************************************** + acstate{1,:}=[sprintf('%s \t\t','GPS Pos:'),'[lat=',num2str(double(sysvector.GPS_Lat(i))*fconv_gpslatlong),'°, ',... + 'lon=',num2str(double(sysvector.GPS_Lon(i))*fconv_gpslatlong),'°, ',... + 'alt=',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{2,:}=[sprintf('%s \t\t','Mags[gauss]'),'[x=',num2str(sysvector.IMU_MagX(i)),... + ', y=',num2str(sysvector.IMU_MagY(i)),... + ', z=',num2str(sysvector.IMU_MagZ(i)),']']; + acstate{3,:}=[sprintf('%s \t\t','Accels[m/s²]'),'[x=',num2str(sysvector.IMU_AccX(i)),... + ', y=',num2str(sysvector.IMU_AccY(i)),... + ', z=',num2str(sysvector.IMU_AccZ(i)),']']; + acstate{4,:}=[sprintf('%s \t\t','Gyros[rad/s]'),'[x=',num2str(sysvector.IMU_GyroX(i)),... + ', y=',num2str(sysvector.IMU_GyroY(i)),... + ', z=',num2str(sysvector.IMU_GyroZ(i)),']']; + acstate{5,:}=[sprintf('%s \t\t','Altitude[m]'),'[Barometric: ',num2str(sysvector.SENS_BaroAlt(i)),'m, GPS: ',num2str(double(sysvector.GPS_Alt(i))*fconv_gpsalt),'m]']; + acstate{6,:}=[sprintf('%s \t','Est. attitude[deg]:'),'[Roll=',num2str(sysvector.ATT_Roll(i).*180./3.14159),... + ', Pitch=',num2str(sysvector.ATT_Pitch(i).*180./3.14159),... + ', Yaw=',num2str(sysvector.ATT_Yaw(i).*180./3.14159),']']; + acstate{7,:}=sprintf('%s \t[','Actuator Ctrls [-]:'); + %for j=1:4 + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Roll(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Pitch(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Yaw(i)),',']; + acstate{7,:}=[acstate{7,:},num2str(sysvector.ATTC_Thrust(i)),',']; + %end + acstate{7,:}=[acstate{7,:},']']; + acstate{8,:}=sprintf('%s \t[','Actuator Outputs [PWM/µs]:'); + %for j=1:8 + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out0(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out1(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out2(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out3(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out4(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out5(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out6(i)),',']; + acstate{8,:}=[acstate{8,:},num2str(sysvector.OUT0_Out7(i)),',']; + %end + acstate{8,:}=[acstate{8,:},']']; + acstate{9,:}=[sprintf('%s \t','Airspeed[m/s]:'),'[IAS: ',num2str(sysvector.AIRS_IndSpeed(i)),', TAS: ',num2str(sysvector.AIRS_TrueSpeed(i)),']']; + + set(h.edits.AircraftState,'String',acstate); + + %********************************************************************** + % GPS Plot Update + %********************************************************************** + %Plot traveled path, and and time. + figure(h.figures(2)); + hold on; + if(CurTime>mintime+1) %the +1 is only a small bugfix + h.pathline=plot3(h.axes(1),double(sysvector.GPS_Lat(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Lon(imintime:i))*fconv_gpslatlong, ... + double(sysvector.GPS_Alt(imintime:i))*fconv_gpsalt,'b','LineWidth',2); + end; + hold off + %Plot current position + newpoint=[double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Lat(i))*fconv_gpslatlong double(sysvector.GPS_Alt(i))*fconv_gpsalt]; + if(numel(h.pathpoints)<=3) %empty path + h.pathpoints(1,1:3)=newpoint; + else %Not empty, append new point + h.pathpoints(size(h.pathpoints,1)+1,:)=newpoint; + end + axes(h.axes(1)); + line(h.pathpoints(:,1),h.pathpoints(:,2),h.pathpoints(:,3),'LineStyle','none','Marker','.','MarkerEdge','black','MarkerSize',20); + + + % Plot current time (small label next to current gps position) + textdesc=strcat(' t=',num2str(time(i)),'s'); + if(isvalidhandle(h.markertext)) + delete(h.markertext); %delete old text + end + h.markertext=text(double(sysvector.GPS_Lat(i))*fconv_gpslatlong,double(sysvector.GPS_Lon(i))*fconv_gpslatlong,... + double(sysvector.GPS_Alt(i))*fconv_gpsalt,textdesc); + set(h.edits.CurTime,'String',CurTime); + + %********************************************************************** + % Plot the lines showing the current time in the 2-d plots + %********************************************************************** + for i=2:NrAxes + if(isvalidhandle(h.markerline(i))) delete(h.markerline(i)); end + ylims=get(h.axes(i),'YLim'); + h.markerline(i)=line([CurTime CurTime] ,get(h.axes(i),'YLim'),'Color','black'); + set(h.markerline(i),'parent',h.axes(i)); + end + + set(h.labels.GUIState,'String','OK','BackgroundColor',[240/255 240/255 240/255]); +end + +%% ************************************************************************ +% MINMAXTIME CALLBACK (nested function) +% ************************************************************************ +function minmaxtime_callback(hObj,event) %#ok + new_mintime=get(h.sliders.MinTime,'Value'); + new_maxtime=get(h.sliders.MaxTime,'Value'); + + %Safety checks: + bErr=false; + %1: mintime must be < maxtime + if((new_mintime>maxtime) || (new_maxtimeCurTime) + set(h.labels.GUIState,'String','Error: Mintime cannot be bigger than CurTime! CurTime set to new mintime.','BackgroundColor','red'); + mintime=new_mintime; + CurTime=mintime; + bErr=true; + end + %3: MaxTime must be >CurTime + if(new_maxtime + %find current time + if(hObj==h.sliders.CurTime) + CurTime=get(h.sliders.CurTime,'Value'); + elseif (hObj==h.edits.CurTime) + temp=str2num(get(h.edits.CurTime,'String')); + if(tempmintime) + CurTime=temp; + else + %Error + set(h.labels.GUIState,'String','Error: You tried to set an invalid current time! Previous value restored.','BackgroundColor','red'); + end + else + %Error + set(h.labels.GUIState,'String','Error: curtime_callback','BackgroundColor','red'); + end + + set(h.sliders.CurTime,'Value',CurTime); + set(h.edits.CurTime,'String',num2str(CurTime)); + + %Redraw time markers, but don't have to redraw the whole raw data + DrawCurrentAircraftState(); +end + +%% ************************************************************************ +% FINDMINMAXINDICES (nested function) +% ************************************************************************ +function [idxmin,idxmax] = FindMinMaxTimeIndices() + for i=1:size(sysvector.TIME_StartTime,1) + if time(i)>=mintime; idxmin=i; break; end + end + for i=1:size(sysvector.TIME_StartTime,1) + if maxtime==0; idxmax=size(sysvector.TIME_StartTime,1); break; end + if time(i)>=maxtime; idxmax=i; break; end + end + mintime=time(idxmin); + maxtime=time(idxmax); +end + +%% ************************************************************************ +% ISVALIDHANDLE (nested function) +% ************************************************************************ +function isvalid = isvalidhandle(handle) + if(exist(varname(handle))>0 && length(ishandle(handle))>0) + if(ishandle(handle)>0) + if(handle>0.0) + isvalid=true; + return; + end + end + end + isvalid=false; +end + +%% ************************************************************************ +% JUST SOME SMALL HELPER FUNCTIONS (nested function) +% ************************************************************************ +function out = varname(var) + out = inputname(1); +end + +%This is the end of the matlab file / the main function +end diff --git a/Tools/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py similarity index 100% rename from Tools/sdlog2_dump.py rename to Tools/sdlog2/sdlog2_dump.py From a8b3381ca9675890b0d36e98a4453ac18d19df3e Mon Sep 17 00:00:00 2001 From: marco Date: Mon, 17 Feb 2014 21:29:14 +0100 Subject: [PATCH 86/87] BL-Ctrl 3.0 fix --- src/drivers/mkblctrl/mkblctrl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mkblctrl/mkblctrl.cpp b/src/drivers/mkblctrl/mkblctrl.cpp index ec5f77d747..705e98eea4 100644 --- a/src/drivers/mkblctrl/mkblctrl.cpp +++ b/src/drivers/mkblctrl/mkblctrl.cpp @@ -705,7 +705,7 @@ MK::mk_check_for_blctrl(unsigned int count, bool showOutput, bool initI2C) Motor[i].State |= MOTOR_STATE_PRESENT_MASK; // set present bit; foundMotorCount++; - if (Motor[i].MaxPWM == 250) { + if ((Motor[i].MaxPWM & 252) == 248) { Motor[i].Version = BLCTRL_NEW; } else { From 4cfaf928e12ac8927b3980506f31c05a1ab899ce Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 18 Feb 2014 16:11:46 +0400 Subject: [PATCH 87/87] px4io: bug in failsafe fixed --- src/modules/px4iofirmware/mixer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index f39fcf7ec6..6a44294619 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -179,7 +179,7 @@ mixer_tick(void) ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ) /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) - /* or failsafe was set manually */ || (r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) + /* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) ) );