diff options
Diffstat (limited to 'src')
-rw-r--r-- | src/drivers/drv_hrt.h | 1 | ||||
-rw-r--r-- | src/lib/geo/geo.h | 2 | ||||
-rw-r--r-- | src/lib/geo/geo_mag_declination.c | 136 | ||||
-rw-r--r-- | src/lib/geo/geo_mag_declination.h (renamed from src/systemcmds/hw_ver/hw_ver.c) | 48 | ||||
-rw-r--r-- | src/lib/geo/module.mk | 3 | ||||
-rw-r--r-- | src/lib/mathlib/CMSIS/Include/arm_math.h | 2 | ||||
-rw-r--r-- | src/modules/mavlink/mavlink_receiver.cpp | 4 | ||||
-rw-r--r-- | src/modules/systemlib/mixer/mixer_load.c | 1 | ||||
-rw-r--r-- | src/systemcmds/pwm/pwm.c | 106 | ||||
-rw-r--r-- | src/systemcmds/ver/module.mk (renamed from src/systemcmds/hw_ver/module.mk) | 11 | ||||
-rw-r--r-- | src/systemcmds/ver/ver.c | 123 |
11 files changed, 390 insertions, 47 deletions
diff --git a/src/drivers/drv_hrt.h b/src/drivers/drv_hrt.h index d130d68b3..8bfc90c64 100644 --- a/src/drivers/drv_hrt.h +++ b/src/drivers/drv_hrt.h @@ -41,6 +41,7 @@ #include <sys/types.h> #include <stdbool.h> +#include <inttypes.h> #include <time.h> #include <queue.h> diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h index 0a3f85d97..e2f3da6f8 100644 --- a/src/lib/geo/geo.h +++ b/src/lib/geo/geo.h @@ -50,6 +50,8 @@ __BEGIN_DECLS +#include "geo/geo_mag_declination.h" + #include <stdbool.h> #define CONSTANTS_ONE_G 9.80665f /* m/s^2 */ diff --git a/src/lib/geo/geo_mag_declination.c b/src/lib/geo/geo_mag_declination.c new file mode 100644 index 000000000..09eac38f4 --- /dev/null +++ b/src/lib/geo/geo_mag_declination.c @@ -0,0 +1,136 @@ +/**************************************************************************** + * + * Copyright (c) 2014 MAV GEO Library (MAVGEO). 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 MAVGEO 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 geo_mag_declination.c +* +* Calculation / lookup table for earth magnetic field declination. +* +* Lookup table from Scott Ferguson <scottfromscott@gmail.com> +* +* XXX Lookup table currently too coarse in resolution (only full degrees) +* and lat/lon res - needs extension medium term. +* +*/ + +#include <geo/geo.h> + +/** set this always to the sampling in degrees for the table below */ +#define SAMPLING_RES 10.0f +#define SAMPLING_MIN_LAT -60.0f +#define SAMPLING_MAX_LAT 60.0f +#define SAMPLING_MIN_LON -180.0f +#define SAMPLING_MAX_LON 180.0f + +static const int8_t declination_table[13][37] = \ +{ + 46, 45, 44, 42, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -40, -48, -55, -61, \ + -66, -71, -74, -75, -72, -61, -25, 22, 40, 45, 47, 46, 30, 30, 30, 30, 29, 29, 29, 29, 27, 24, 18, 11, 3, \ + -3, -9, -12, -15, -17, -21, -26, -32, -39, -45, -51, -55, -57, -56, -53, -44, -31, -14, 0, 13, 21, 26, \ + 29, 30, 21, 22, 22, 22, 22, 22, 22, 22, 21, 18, 13, 5, -3, -11, -17, -20, -21, -22, -23, -25, -29, -35, \ + -40, -44, -45, -44, -40, -32, -22, -12, -3, 3, 9, 14, 18, 20, 21, 16, 17, 17, 17, 17, 17, 16, 16, 16, 13, \ + 8, 0, -9, -16, -21, -24, -25, -25, -23, -20, -21, -24, -28, -31, -31, -29, -24, -17, -9, -3, 0, 4, 7, \ + 10, 13, 15, 16, 12, 13, 13, 13, 13, 13, 12, 12, 11, 9, 3, -4, -12, -19, -23, -24, -24, -22, -17, -12, -9, \ + -10, -13, -17, -18, -16, -13, -8, -3, 0, 1, 3, 6, 8, 10, 12, 12, 10, 10, 10, 10, 10, 10, 10, 9, 9, 6, 0, -6, \ + -14, -20, -22, -22, -19, -15, -10, -6, -2, -2, -4, -7, -8, -8, -7, -4, 0, 1, 1, 2, 4, 6, 8, 10, 10, 9, 9, 9, \ + 9, 9, 9, 8, 8, 7, 4, -1, -8, -15, -19, -20, -18, -14, -9, -5, -2, 0, 1, 0, -2, -3, -4, -3, -2, 0, 0, 0, 1, 3, 5, \ + 7, 8, 9, 8, 8, 8, 9, 9, 9, 8, 8, 6, 2, -3, -9, -15, -18, -17, -14, -10, -6, -2, 0, 1, 2, 2, 0, -1, -1, -2, -1, 0, \ + 0, 0, 0, 1, 3, 5, 7, 8, 8, 9, 9, 10, 10, 10, 10, 8, 5, 0, -5, -11, -15, -16, -15, -12, -8, -4, -1, 0, 2, 3, 2, 1, 0, \ + 0, 0, 0, 0, -1, -2, -2, -1, 0, 3, 6, 8, 6, 9, 10, 11, 12, 12, 11, 9, 5, 0, -7, -12, -15, -15, -13, -10, -7, -3, \ + 0, 1, 2, 3, 3, 3, 2, 1, 0, 0, -1, -3, -4, -5, -5, -2, 0, 3, 6, 5, 8, 11, 13, 15, 15, 14, 11, 5, -1, -9, -14, -17, \ + -16, -14, -11, -7, -3, 0, 1, 3, 4, 5, 5, 5, 4, 3, 1, -1, -4, -7, -8, -8, -6, -2, 1, 5, 4, 8, 12, 15, 17, 18, 16, \ + 12, 5, -3, -12, -18, -20, -19, -16, -13, -8, -4, -1, 1, 4, 6, 8, 9, 9, 9, 7, 3, -1, -6, -10, -12, -11, -9, -5, \ + 0, 4, 3, 9, 14, 17, 20, 21, 19, 14, 4, -8, -19, -25, -26, -25, -21, -17, -12, -7, -2, 1, 5, 9, 13, 15, 16, 16, \ + 13, 7, 0, -7, -12, -15, -14, -11, -6, -1, 3 +}; + +static float get_lookup_table_val(unsigned lat, unsigned lon); + +__EXPORT float get_mag_declination(float lat, float lon) +{ + /* + * If the values exceed valid ranges, return zero as default + * as we have no way of knowing what the closest real value + * would be. + */ + if (lat < -90.0f || lat > 90.0f || + lon < -180.0f || lon > 180.0f) { + return 0.0f; + } + + /* round down to nearest sampling resolution */ + int min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES; + int min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES; + + /* for the rare case of hitting the bounds exactly + * the rounding logic wouldn't fit, so enforce it. + */ + + /* limit to table bounds - required for maxima even when table spans full globe range */ + if (lat <= SAMPLING_MIN_LAT) { + min_lat = SAMPLING_MIN_LAT; + } + + if (lat >= SAMPLING_MAX_LAT) { + min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES; + } + + if (lon <= SAMPLING_MIN_LON) { + min_lon = SAMPLING_MIN_LON; + } + + if (lon >= SAMPLING_MAX_LON) { + min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES; + } + + /* find index of nearest low sampling point */ + unsigned min_lat_index = (-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES; + unsigned min_lon_index = (-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES; + + float declination_sw = get_lookup_table_val(min_lat_index, min_lon_index); + float declination_se = get_lookup_table_val(min_lat_index, min_lon_index + 1); + float declination_ne = get_lookup_table_val(min_lat_index + 1, min_lon_index + 1); + float declination_nw = get_lookup_table_val(min_lat_index + 1, min_lon_index); + + /* perform bilinear interpolation on the four grid corners */ + + float declination_min = ((lon - min_lon) / SAMPLING_RES) * (declination_se - declination_sw) + declination_sw; + float declination_max = ((lon - min_lon) / SAMPLING_RES) * (declination_ne - declination_nw) + declination_nw; + + return ((lat - min_lat) / SAMPLING_RES) * (declination_max - declination_min) + declination_min; +} + +float get_lookup_table_val(unsigned lat_index, unsigned lon_index) +{ + return declination_table[lat_index][lon_index]; +}
\ No newline at end of file diff --git a/src/systemcmds/hw_ver/hw_ver.c b/src/lib/geo/geo_mag_declination.h index 4b84523cc..0ac062d6d 100644 --- a/src/systemcmds/hw_ver/hw_ver.c +++ b/src/lib/geo/geo_mag_declination.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * Copyright (c) 2014 MAV GEO Library (MAVGEO). All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -12,7 +12,7 @@ * 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 + * 3. Neither the name MAVGEO nor the names of its contributors may be * used to endorse or promote products derived from this software * without specific prior written permission. * @@ -32,42 +32,16 @@ ****************************************************************************/ /** - * @file hw_ver.c - * - * Show and test hardware version. - */ - -#include <nuttx/config.h> - -#include <stdio.h> -#include <string.h> -#include <errno.h> -#include <version/version.h> - -__EXPORT int hw_ver_main(int argc, char *argv[]); +* @file geo_mag_declination.h +* +* Calculation / lookup table for earth magnetic field declination. +* +*/ -int -hw_ver_main(int argc, char *argv[]) -{ - if (argc >= 2) { - if (!strcmp(argv[1], "show")) { - printf(HW_ARCH "\n"); - exit(0); - } +#pragma once - if (!strcmp(argv[1], "compare")) { - if (argc >= 3) { - int ret = strcmp(HW_ARCH, argv[2]) != 0; - if (ret == 0) { - printf("hw_ver match: %s\n", HW_ARCH); - } - exit(ret); +__BEGIN_DECLS - } else { - errx(1, "not enough arguments, try 'compare PX4FMU_1'"); - } - } - } +__EXPORT float get_mag_declination(float lat, float lon); - errx(1, "expected a command, try 'show' or 'compare'"); -} +__END_DECLS diff --git a/src/lib/geo/module.mk b/src/lib/geo/module.mk index 30a2dc99f..9500a2bcc 100644 --- a/src/lib/geo/module.mk +++ b/src/lib/geo/module.mk @@ -35,4 +35,5 @@ # Geo library # -SRCS = geo.c +SRCS = geo.c \ + geo_mag_declination.c diff --git a/src/lib/mathlib/CMSIS/Include/arm_math.h b/src/lib/mathlib/CMSIS/Include/arm_math.h index 6f66f9ee3..61d3a3b61 100644 --- a/src/lib/mathlib/CMSIS/Include/arm_math.h +++ b/src/lib/mathlib/CMSIS/Include/arm_math.h @@ -5193,7 +5193,7 @@ void arm_rfft_fast_f32( *pIa = Ialpha;
/* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */
- *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
+ *pIb = (float32_t)-0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
}
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 33a4fef12..7c93c1c00 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -432,8 +432,8 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) memset(&manual, 0, sizeof(manual)); manual.timestamp = hrt_absolute_time(); - manual.roll = man.x / 1000.0f; - manual.pitch = man.y / 1000.0f; + manual.pitch = man.x / 1000.0f; + manual.roll = man.y / 1000.0f; manual.yaw = man.r / 1000.0f; manual.throttle = man.z / 1000.0f; diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c index b05273c0d..bf3428a50 100644 --- a/src/modules/systemlib/mixer/mixer_load.c +++ b/src/modules/systemlib/mixer/mixer_load.c @@ -41,6 +41,7 @@ #include <string.h> #include <stdio.h> #include <ctype.h> +#include <systemlib/err.h> #include "mixer_load.h" diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 7c23f38c2..1828c660f 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -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 @@ -443,6 +443,110 @@ pwm_main(int argc, char *argv[]) exit(0); } } + usleep(2000); + } + exit(0); + + + } else if (!strcmp(argv[1], "steps")) { + + if (set_mask == 0) { + usage("no channels set"); + } + + /* get current servo values */ + struct pwm_output_values last_spos; + + for (unsigned i = 0; i < servo_count; i++) { + + ret = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&last_spos.values[i]); + if (ret != OK) + err(1, "PWM_SERVO_GET(%d)", i); + } + + /* perform PWM output */ + + /* Open console directly to grab CTRL-C signal */ + struct pollfd fds; + fds.fd = 0; /* stdin */ + fds.events = POLLIN; + + warnx("Running 5 steps. WARNING! Motors will be live in 5 seconds\nPress any key to abort now."); + sleep(5); + + unsigned off = 900; + unsigned idle = 1300; + unsigned full = 2000; + unsigned steps_timings_us[] = {2000, 5000, 20000, 50000}; + + unsigned phase = 0; + unsigned phase_counter = 0; + unsigned const phase_maxcount = 20; + + for ( unsigned steps_timing_index = 0; + steps_timing_index < sizeof(steps_timings_us) / sizeof(steps_timings_us[0]); + steps_timing_index++ ) { + + warnx("Sending step input with 0 to 100%% over a %u microseconds ramp", steps_timings_us[steps_timing_index]); + + while (1) { + for (unsigned i = 0; i < servo_count; i++) { + if (set_mask & 1<<i) { + + unsigned val; + + if (phase == 0) { + val = idle; + } else if (phase == 1) { + /* ramp - depending how steep it is this ramp will look instantaneous on the output */ + val = idle + (full - idle) * (phase_maxcount / (float)phase_counter); + } else { + val = off; + } + + ret = ioctl(fd, PWM_SERVO_SET(i), val); + if (ret != OK) + err(1, "PWM_SERVO_SET(%d)", i); + } + } + + /* abort on user request */ + char c; + ret = poll(&fds, 1, 0); + if (ret > 0) { + + int ret = read(0, &c, 1); + if (ret > 0) { + /* reset output to the last value */ + for (unsigned i = 0; i < servo_count; i++) { + if (set_mask & 1<<i) { + ret = ioctl(fd, PWM_SERVO_SET(i), last_spos.values[i]); + if (ret != OK) + err(1, "PWM_SERVO_SET(%d)", i); + } + } + warnx("Key pressed, user abort\n"); + exit(0); + } + } + if (phase == 1) { + usleep(steps_timings_us[steps_timing_index] / phase_maxcount); + + } else if (phase == 0) { + usleep(50000); + } else if (phase == 2) { + usleep(50000); + } else { + break; + } + + phase_counter++; + + if (phase_counter > phase_maxcount) { + phase++; + phase_counter = 0; + } + } } exit(0); diff --git a/src/systemcmds/hw_ver/module.mk b/src/systemcmds/ver/module.mk index 3cc08b6a1..2eeb80b61 100644 --- a/src/systemcmds/hw_ver/module.mk +++ b/src/systemcmds/ver/module.mk @@ -32,12 +32,13 @@ ############################################################################ # -# Show and test hardware version +# "version" nsh-command displays version infromation for hw,sw, gcc,build etc +# can be also included and used in own code via "ver.h" # -MODULE_COMMAND = hw_ver -SRCS = hw_ver.c +MODULE_COMMAND = ver +SRCS = ver.c -MODULE_STACKSIZE = 1024 +MODULE_STACKSIZE = 1024 -MAXOPTIMIZATION = -Os +MAXOPTIMIZATION = -Os diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c new file mode 100644 index 000000000..9ae080ee2 --- /dev/null +++ b/src/systemcmds/ver/ver.c @@ -0,0 +1,123 @@ +/**************************************************************************** +* +* 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 ver.c +* +* Version command, unifies way of showing versions of HW, SW, Build, GCC +* In case you want to add new version just extend version_main function +* +* @author Vladimir Kulla <ufon@kullaonline.net> +*/ + +#include <stdio.h> +#include <string.h> +#include <version/version.h> +#include <systemlib/err.h> + +// string constants for version commands +static const char sz_ver_hw_str[] = "hw"; +static const char sz_ver_hwcmp_str[] = "hwcmp"; +static const char sz_ver_git_str[] = "git"; +static const char sz_ver_bdate_str[] = "bdate"; +static const char sz_ver_gcc_str[] = "gcc"; +static const char sz_ver_all_str[] = "all"; + +static void usage(const char *reason) +{ + if (reason != NULL) { + printf("%s\n", reason); + } + + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all}\n\n"); +} + +__EXPORT int ver_main(int argc, char *argv[]); + +int ver_main(int argc, char *argv[]) +{ + int ret = 1; //defaults to an error + + // first check if there are at least 2 params + if (argc >= 2) { + if (argv[1] != NULL) { + if (!strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { + printf("%s\n", HW_ARCH); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_hwcmp_str, sizeof(sz_ver_hwcmp_str))) { + if (argc >= 3 && argv[2] != NULL) { + // compare 3rd parameter with HW_ARCH string, in case of match, return 0 + ret = strncmp(HW_ARCH, argv[2], strlen(HW_ARCH)); + + if (ret == 0) { + printf("ver hwcmp match: %s\n", HW_ARCH); + } + + } else { + errx(1, "Not enough arguments, try 'ver hwcmp PX4FMU_V2'"); + } + + } else if (!strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) { + printf("%s\n", FW_GIT); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { + printf("%s %s\n", __DATE__, __TIME__); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { + printf("%s\n", __VERSION__); + ret = 0; + + } else if (!strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str))) { + printf("HW arch: %s\n", HW_ARCH); + printf("Build datetime: %s %s\n", __DATE__, __TIME__); + printf("FW git-hash: %s\n", FW_GIT); + printf("GCC toolchain: %s\n", __VERSION__); + ret = 0; + + } else { + errx(1, "unknown command.\n"); + } + + } else { + usage("Error, input parameter NULL.\n"); + } + + } else { + usage("Error, not enough parameters."); + } + + return ret; +} |