From 6ece4cf7c44869d2fd6e027ad6239baf3af860df Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Tue, 26 Aug 2014 21:08:16 +0200 Subject: ORB topic for drive testing requests --- src/modules/uORB/objects_common.cpp | 3 ++ src/modules/uORB/topics/test_motor.h | 70 ++++++++++++++++++++++++++++++++++++ 2 files changed, 73 insertions(+) create mode 100644 src/modules/uORB/topics/test_motor.h diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index f7d5f8737..b8cdb45eb 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -198,6 +198,9 @@ ORB_DEFINE(telemetry_status_1, struct telemetry_status_s); ORB_DEFINE(telemetry_status_2, struct telemetry_status_s); ORB_DEFINE(telemetry_status_3, struct telemetry_status_s); +#include "topics/test_motor.h" +ORB_DEFINE(test_motor, struct test_motor_s); + #include "topics/debug_key_value.h" ORB_DEFINE(debug_key_value, struct debug_key_value_s); diff --git a/src/modules/uORB/topics/test_motor.h b/src/modules/uORB/topics/test_motor.h new file mode 100644 index 000000000..491096934 --- /dev/null +++ b/src/modules/uORB/topics/test_motor.h @@ -0,0 +1,70 @@ +/**************************************************************************** + * + * 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 test_motor.h + * + * Test a single drive motor while the vehicle is disarmed + * + * Publishing values to this topic causes a single motor to spin, e.g. for + * ground test purposes. This topic will be ignored while the vehicle is armed. + * + */ + +#ifndef TOPIC_TEST_MOTOR_H +#define TOPIC_TEST_MOTOR_H + +#include +#include "../uORB.h" + +#define NUM_MOTOR_OUTPUTS 8 + +/** + * @addtogroup topics + * @{ + */ + +struct test_motor_s { + uint64_t timestamp; /**< output timestamp in us since system boot */ + unsigned motor_number; /**< number of motor to spin */ + float value; /**< output data, in natural output units */ +}; + +/** + * @} + */ + +/* actuator output sets; this list can be expanded as more drivers emerge */ +ORB_DECLARE(test_motor); + +#endif -- cgit v1.2.3 From f8ba5f8dae146529e3ff28f4330cdc4daaa6f260 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Tue, 26 Aug 2014 21:10:39 +0200 Subject: cmd line utility for controlling drive tests --- src/systemcmds/motor_test/module.mk | 41 +++++++++++ src/systemcmds/motor_test/motor_test.c | 128 +++++++++++++++++++++++++++++++++ 2 files changed, 169 insertions(+) create mode 100644 src/systemcmds/motor_test/module.mk create mode 100644 src/systemcmds/motor_test/motor_test.c diff --git a/src/systemcmds/motor_test/module.mk b/src/systemcmds/motor_test/module.mk new file mode 100644 index 000000000..eb36d2ded --- /dev/null +++ b/src/systemcmds/motor_test/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# 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. +# +############################################################################ + +# +# Build the motor_test tool. +# + +MODULE_COMMAND = motor_test +SRCS = motor_test.c + +MODULE_STACKSIZE = 4096 diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c new file mode 100644 index 000000000..079f99674 --- /dev/null +++ b/src/systemcmds/motor_test/motor_test.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: Holger Steinhaus + * + * 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 motor_test.c + * + * Tool for drive testing + */ + +#include + +#include +#include +#include +#include + +#include +#include +#include + + +#include "systemlib/systemlib.h" +#include "systemlib/err.h" + + +__EXPORT int motor_test_main(int argc, char *argv[]); +static void motor_test(unsigned channel, float value); +static void usage(const char *reason); + +void motor_test(unsigned channel, float value) +{ + orb_advert_t _test_motor_pub; + struct test_motor_s _test_motor; + + _test_motor.motor_number = channel; + _test_motor.timestamp = hrt_absolute_time(); + _test_motor.value = value; + + if (_test_motor_pub > 0) { + /* publish armed state */ + orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor); + } else { + /* advertise and publish */ + _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor); + } +} + +static void usage(const char *reason) +{ + if (reason != NULL) + warnx("%s", reason); + + errx(1, + "usage:\n" + "motor_test\n" + " -m Motor to test (0..7)\n" + " -p Power (0..100)\n"); +} + +int motor_test_main(int argc, char *argv[]) +{ + unsigned long channel, lval; + float value; + int ch; + + if (argc != 5) { + usage("please specify motor and power"); + } + + while ((ch = getopt(argc, argv, "m:p:")) != EOF) { + switch (ch) { + + case 'm': + /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ + channel = strtoul(optarg, NULL, 0); + break; + + case 'p': + /* Read in custom low value */ + lval = strtoul(optarg, NULL, 0); + + if (lval > 100) + usage("value invalid"); + + value = (float)lval/100.f; + break; + default: + usage(NULL); + } + } + + motor_test(channel, value); + + printf("motor %d set to %.2f\n", channel, value); + + exit(0); +} -- cgit v1.2.3 From 0d917576d484d2e2dc0233c5545a16e36f6e2f41 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 15 Oct 2014 22:19:06 +0200 Subject: Enable flaps in manual override --- src/drivers/px4io/px4io.cpp | 9 ++++++++- src/modules/px4iofirmware/controls.c | 14 +++++++++++--- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index d212be766..73160b2d9 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1265,11 +1265,18 @@ PX4IO::io_set_rc_config() if ((ichan >= 0) && (ichan < (int)_max_rc_input)) input_map[ichan - 1] = 3; - param_get(param_find("RC_MAP_MODE_SW"), &ichan); + param_get(param_find("RC_MAP_FLAPS"), &ichan); if ((ichan >= 0) && (ichan < (int)_max_rc_input)) input_map[ichan - 1] = 4; + param_get(param_find("RC_MAP_MODE_SW"), &ichan); + + if ((ichan >= 0) && (ichan < (int)_max_rc_input)) { + /* use out of normal bounds index to indicate special channel */ + input_map[ichan - 1] = 8; + } + /* * Iterate all possible RC inputs. */ diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 7b127759a..0b0832d55 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -60,6 +60,8 @@ static perf_counter_t c_gather_ppm; static int _dsm_fd; +static uint16_t rc_value_override = 0; + bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated) { perf_begin(c_gather_dsm); @@ -313,8 +315,14 @@ controls_tick() { } } - r_rc_values[mapped] = SIGNED_TO_REG(scaled); - assigned_channels |= (1 << mapped); + /* pick out override channel, indicated by mapping 8 (9 th channel, virtual) */ + if (mapped == 8) { + rc_value_override = SIGNED_TO_REG(scaled); + } else { + /* normal channel */ + r_rc_values[mapped] = SIGNED_TO_REG(scaled); + assigned_channels |= (1 << mapped); + } } } @@ -409,7 +417,7 @@ controls_tick() { * requested override. * */ - if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(r_rc_values[4]) < RC_CHANNEL_LOW_THRESH)) + if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(rc_value_override) < RC_CHANNEL_LOW_THRESH)) override = true; if (override) { -- cgit v1.2.3 From f4903316329ca91b9e872327f701de5b6a2cc13c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 16 Oct 2014 22:57:27 +0200 Subject: Enable flaps, avoid mode switch position --- src/drivers/px4io/px4io.cpp | 2 +- src/modules/px4iofirmware/controls.c | 13 +++++-------- src/modules/px4iofirmware/mixer.cpp | 7 ------- src/modules/px4iofirmware/protocol.h | 1 + src/modules/px4iofirmware/registers.c | 3 ++- 5 files changed, 9 insertions(+), 17 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 73160b2d9..3871b4a2c 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1274,7 +1274,7 @@ PX4IO::io_set_rc_config() if ((ichan >= 0) && (ichan < (int)_max_rc_input)) { /* use out of normal bounds index to indicate special channel */ - input_map[ichan - 1] = 8; + input_map[ichan - 1] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH; } /* diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 0b0832d55..ad60ee03e 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -315,15 +315,12 @@ controls_tick() { } } - /* pick out override channel, indicated by mapping 8 (9 th channel, virtual) */ - if (mapped == 8) { - rc_value_override = SIGNED_TO_REG(scaled); - } else { - /* normal channel */ - r_rc_values[mapped] = SIGNED_TO_REG(scaled); - assigned_channels |= (1 << mapped); - } + r_rc_values[mapped] = SIGNED_TO_REG(scaled); + assigned_channels |= (1 << mapped); + } else if (mapped == PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH) { + /* pick out override channel, indicated by special mapping */ + rc_value_override = SIGNED_TO_REG(scaled); } } } diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 3e19333d8..c0b8ac358 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -60,13 +60,6 @@ extern "C" { */ #define FMU_INPUT_DROP_LIMIT_US 500000 -/* XXX need to move the RC_CHANNEL_FUNCTION out of rc_channels.h and into systemlib */ -#define ROLL 0 -#define PITCH 1 -#define YAW 2 -#define THROTTLE 3 -#define OVERRIDE 4 - /* current servo arm/disarm state */ static bool mixer_servos_armed = false; static bool should_arm = false; diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index 89a470b44..a3e8a58d3 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -246,6 +246,7 @@ enum { /* DSM bind states */ #define PX4IO_P_RC_CONFIG_MAX 2 /**< highest input value */ #define PX4IO_P_RC_CONFIG_DEADZONE 3 /**< band around center that is ignored */ #define PX4IO_P_RC_CONFIG_ASSIGNMENT 4 /**< mapped input value */ +#define PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH 100 /**< magic value for mode switch */ #define PX4IO_P_RC_CONFIG_OPTIONS 5 /**< channel options bitmask */ #define PX4IO_P_RC_CONFIG_OPTIONS_ENABLED (1 << 0) #define PX4IO_P_RC_CONFIG_OPTIONS_REVERSE (1 << 1) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 7a5a5e484..7f19e983f 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -686,7 +686,8 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] == UINT8_MAX) { disabled = true; - } else if (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) { + } else if ((conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] >= PX4IO_RC_MAPPED_CONTROL_CHANNELS) && + (conf[PX4IO_P_RC_CONFIG_ASSIGNMENT] != PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH)) { count++; } -- cgit v1.2.3 From 99f839b03861a9868f366c63cd214aa5898414aa Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Thu, 23 Oct 2014 10:57:31 +0200 Subject: Add a min PWM output so motors idle on arming. --- ROMFS/px4fmu_common/init.d/10015_tbs_discovery | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index c4be16943..b1aa8c00b 100644 --- a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery +++ b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery @@ -27,3 +27,4 @@ fi set MIXER FMU_quad_w set PWM_OUTPUTS 1234 +set PWM_MIN 1200 -- cgit v1.2.3 From f3cda1839624b22bca8b030a43b72e8c0e354ab3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 23 Oct 2014 16:17:20 +0200 Subject: Formatting commander.cpp to simplify later rework by ensuring formatting match. NO CODE CHANGES --- src/modules/commander/commander.cpp | 247 +++++++++++++++++++++++------------- 1 file changed, 159 insertions(+), 88 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 616b855df..cb507c9ba 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -207,7 +207,9 @@ void usage(const char *reason); /** * React to commands that are sent e.g. from the mavlink module. */ -bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub); +bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, + struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, + orb_advert_t *home_pub); /** * Mainloop of commander. @@ -230,7 +232,8 @@ void print_reject_arm(const char *msg); void print_status(); -transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos); +transition_result_t check_navigation_state_machine(struct vehicle_status_s *status, + struct vehicle_control_mode_s *control_mode, struct vehicle_local_position_s *local_pos); transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy); @@ -393,7 +396,8 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char // Transition the armed state. By passing mavlink_fd to arming_state_transition it will // output appropriate error messages if the state cannot transition. - arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd_local); + arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, + true /* fRunPreArmChecks */, mavlink_fd_local); if (arming_res == TRANSITION_CHANGED && mavlink_fd) { mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy); @@ -406,11 +410,12 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char } bool handle_command(struct vehicle_status_s *status_local, const struct safety_s *safety_local, - struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local, - struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub) + struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local, + struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub) { /* only handle commands that are meant to be handled by this system and component */ - if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components + if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) + && (cmd->target_component != 0))) { // component_id 0: valid for all components return false; } @@ -537,13 +542,13 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s } else { mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f", - (double)cmd->param1, - (double)cmd->param2, - (double)cmd->param3, - (double)cmd->param4, - (double)cmd->param5, - (double)cmd->param6, - (double)cmd->param7); + (double)cmd->param1, + (double)cmd->param2, + (double)cmd->param3, + (double)cmd->param4, + (double)cmd->param5, + (double)cmd->param6, + (double)cmd->param7); } } break; @@ -554,35 +559,43 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s //XXX update state machine? armed_local->force_failsafe = true; warnx("forcing failsafe (termination)"); + } else { armed_local->force_failsafe = false; warnx("disabling failsafe (termination)"); } + /* param2 is currently used for other failsafe modes */ status_local->engine_failure_cmd = false; status_local->data_link_lost_cmd = false; status_local->gps_failure_cmd = false; status_local->rc_signal_lost_cmd = false; + if ((int)cmd->param2 <= 0) { /* reset all commanded failure modes */ warnx("reset all non-flighttermination failsafe commands"); + } else if ((int)cmd->param2 == 1) { /* trigger engine failure mode */ status_local->engine_failure_cmd = true; warnx("engine failure mode commanded"); + } else if ((int)cmd->param2 == 2) { /* trigger data link loss mode */ status_local->data_link_lost_cmd = true; warnx("data link loss mode commanded"); + } else if ((int)cmd->param2 == 3) { /* trigger gps loss mode */ status_local->gps_failure_cmd = true; warnx("gps loss mode commanded"); + } else if ((int)cmd->param2 == 4) { /* trigger rc loss mode */ status_local->rc_signal_lost_cmd = true; warnx("rc loss mode commanded"); } + cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; } break; @@ -633,21 +646,27 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s } } break; + case VEHICLE_CMD_NAV_GUIDED_ENABLE: { transition_result_t res = TRANSITION_DENIED; static main_state_t main_state_pre_offboard = MAIN_STATE_MANUAL; + if (status_local->main_state != MAIN_STATE_OFFBOARD) { main_state_pre_offboard = status_local->main_state; } + if (cmd->param1 > 0.5f) { res = main_state_transition(status_local, MAIN_STATE_OFFBOARD); + if (res == TRANSITION_DENIED) { print_reject_mode(status_local, "OFFBOARD"); status_local->offboard_control_set_by_command = false; + } else { /* Set flag that offboard was set via command, main state is not overridden by rc */ status_local->offboard_control_set_by_command = true; } + } else { /* If the mavlink command is used to enable or disable offboard control: * switch back to previous mode when disabling */ @@ -656,6 +675,7 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s } } break; + case VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN: case VEHICLE_CMD_PREFLIGHT_CALIBRATION: case VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS: @@ -802,6 +822,7 @@ int commander_thread_main(int argc, char *argv[]) /* publish initial state */ status_pub = orb_advertise(ORB_ID(vehicle_status), &status); + if (status_pub < 0) { warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n"); warnx("exiting."); @@ -827,11 +848,14 @@ int commander_thread_main(int argc, char *argv[]) /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */ orb_advert_t mission_pub = -1; mission_s mission; + if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) { if (mission.dataman_id >= 0 && mission.dataman_id <= 1) { - warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq); + warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, + mission.current_seq); mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d", - mission.dataman_id, mission.count, mission.current_seq); + mission.dataman_id, mission.count, mission.current_seq); + } else { const char *missionfail = "reading mission state failed"; warnx("%s", missionfail); @@ -1097,6 +1121,7 @@ int commander_thread_main(int argc, char *argv[]) status.offboard_control_signal_lost = false; status_changed = true; } + } else { if (!status.offboard_control_signal_lost) { status.offboard_control_signal_lost = true; @@ -1115,9 +1140,9 @@ int commander_thread_main(int argc, char *argv[]) /* perform system checks when new telemetry link connected */ if (mavlink_fd && - telemetry_last_heartbeat[i] == 0 && - telemetry.heartbeat_time > 0 && - hrt_elapsed_time(&telemetry.heartbeat_time) < datalink_loss_timeout * 1e6) { + telemetry_last_heartbeat[i] == 0 && + telemetry.heartbeat_time > 0 && + hrt_elapsed_time(&telemetry.heartbeat_time) < datalink_loss_timeout * 1e6) { (void)rc_calibration_check(mavlink_fd); } @@ -1130,6 +1155,7 @@ int commander_thread_main(int argc, char *argv[]) if (updated) { orb_copy(ORB_ID(sensor_combined), sensor_sub, &sensors); + /* Check if the barometer is healthy and issue a warning in the GCS if not so. * Because the barometer is used for calculating AMSL altitude which is used to ensure * vertical separation from other airtraffic the operator has to know when the @@ -1142,6 +1168,7 @@ int commander_thread_main(int argc, char *argv[]) status_changed = true; mavlink_log_critical(mavlink_fd, "baro healthy"); } + } else { if (!status.barometer_failure) { status.barometer_failure = true; @@ -1164,10 +1191,11 @@ int commander_thread_main(int argc, char *argv[]) if (hrt_elapsed_time(&system_power.timestamp) < 200000) { if (system_power.servo_valid && - !system_power.brick_valid && - !system_power.usb_connected) { + !system_power.brick_valid && + !system_power.usb_connected) { /* flying only on servo rail, this is unsafe */ status.condition_power_input_valid = false; + } else { status.condition_power_input_valid = true; } @@ -1187,9 +1215,11 @@ int commander_thread_main(int argc, char *argv[]) /* disarm if safety is now on and still armed */ if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) { - arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); + arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : + ARMING_STATE_STANDBY_ERROR); - if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */, mavlink_fd)) { + if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, + true /* fRunPreArmChecks */, mavlink_fd)) { mavlink_log_info(mavlink_fd, "DISARMED by safety switch"); arming_state_changed = true; } @@ -1233,7 +1263,8 @@ int commander_thread_main(int argc, char *argv[]) } } - check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), &status_changed); + check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), + &status_changed); /* update home position */ if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed && @@ -1283,8 +1314,11 @@ int commander_thread_main(int argc, char *argv[]) local_eph_good = false; } } - check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid && local_eph_good, &(status.condition_local_position_valid), &status_changed); - check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, &(status.condition_local_altitude_valid), &status_changed); + + check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.xy_valid + && local_eph_good, &(status.condition_local_position_valid), &status_changed); + check_valid(local_position.timestamp, POSITION_TIMEOUT, local_position.z_valid, + &(status.condition_local_altitude_valid), &status_changed); if (status.condition_local_altitude_valid) { if (status.condition_landed != local_position.landed) { @@ -1315,7 +1349,8 @@ int commander_thread_main(int argc, char *argv[]) /* get throttle (if armed), as we only care about energy negative throttle also counts */ float throttle = (armed.armed) ? fabsf(actuator_controls.control[3]) : 0.0f; - status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah, throttle); + status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah, + throttle); } } @@ -1383,26 +1418,30 @@ int commander_thread_main(int argc, char *argv[]) status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; - } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.09f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { + } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.09f + && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY"); status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL; if (armed.armed) { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, true /* fRunPreArmChecks */, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, true /* fRunPreArmChecks */, + mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } } else { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, true /* fRunPreArmChecks */, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, true /* fRunPreArmChecks */, + mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } } + status_changed = true; } @@ -1411,7 +1450,8 @@ int commander_thread_main(int argc, char *argv[]) /* If in INIT state, try to proceed to STANDBY state */ if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) { /* TODO: check for sensors */ - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, + mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; @@ -1439,23 +1479,25 @@ int commander_thread_main(int argc, char *argv[]) /* Initialize map projection if gps is valid */ if (!map_projection_global_initialized() - && (gps_position.eph < eph_threshold) - && (gps_position.epv < epv_threshold) - && hrt_elapsed_time((hrt_abstime*)&gps_position.timestamp_position) < 1e6) { + && (gps_position.eph < eph_threshold) + && (gps_position.epv < epv_threshold) + && hrt_elapsed_time((hrt_abstime *)&gps_position.timestamp_position) < 1e6) { /* set reference for global coordinates <--> local coordiantes conversion and map_projection */ - globallocalconverter_init((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7, (float)gps_position.alt * 1.0e-3f, hrt_absolute_time()); + globallocalconverter_init((double)gps_position.lat * 1.0e-7, (double)gps_position.lon * 1.0e-7, + (float)gps_position.alt * 1.0e-3f, hrt_absolute_time()); } /* check if GPS fix is ok */ if (status.circuit_breaker_engaged_gpsfailure_check || - (gps_position.fix_type >= 3 && - hrt_elapsed_time(&gps_position.timestamp_position) < FAILSAFE_DEFAULT_TIMEOUT)) { + (gps_position.fix_type >= 3 && + hrt_elapsed_time(&gps_position.timestamp_position) < FAILSAFE_DEFAULT_TIMEOUT)) { /* handle the case where gps was regained */ if (status.gps_failure) { status.gps_failure = false; status_changed = true; mavlink_log_critical(mavlink_fd, "gps regained"); } + } else { if (!status.gps_failure) { status.gps_failure = true; @@ -1477,12 +1519,14 @@ int commander_thread_main(int argc, char *argv[]) armed.force_failsafe = true; status_changed = true; static bool flight_termination_printed = false; + if (!flight_termination_printed) { warnx("Flight termination because of navigator request or geofence"); mavlink_log_critical(mavlink_fd, "GF violation: flight termination"); flight_termination_printed = true; } - if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 ) { + + if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { mavlink_log_critical(mavlink_fd, "GF violation: flight termination"); } } // no reset is done here on purpose, on geofence violation we want to stay in flighttermination @@ -1490,7 +1534,7 @@ int commander_thread_main(int argc, char *argv[]) /* RC input check */ if (!status.rc_input_blocked && sp_man.timestamp != 0 && - hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) { + hrt_absolute_time() < sp_man.timestamp + (uint64_t)(rc_loss_timeout * 1e6f)) { /* handle the case where RC signal was regained */ if (!status.rc_signal_found_once) { status.rc_signal_found_once = true; @@ -1515,11 +1559,15 @@ int commander_thread_main(int argc, char *argv[]) if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */ - arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); - arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */, mavlink_fd); + arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : + ARMING_STATE_STANDBY_ERROR); + arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */, + mavlink_fd); + if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } + stick_off_counter = 0; } else { @@ -1541,8 +1589,11 @@ int commander_thread_main(int argc, char *argv[]) */ if (status.main_state != MAIN_STATE_MANUAL) { print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); + } else { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, true /* fRunPreArmChecks */, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, true /* fRunPreArmChecks */, + mavlink_fd); + if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } @@ -1565,6 +1616,7 @@ int commander_thread_main(int argc, char *argv[]) } else { mavlink_log_info(mavlink_fd, "DISARMED by RC"); } + arming_state_changed = true; } else if (arming_ret == TRANSITION_DENIED) { @@ -1600,18 +1652,20 @@ int commander_thread_main(int argc, char *argv[]) /* data links check */ bool have_link = false; + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { if (telemetry_last_heartbeat[i] != 0 && - hrt_elapsed_time(&telemetry_last_heartbeat[i]) < datalink_loss_timeout * 1e6) { + hrt_elapsed_time(&telemetry_last_heartbeat[i]) < datalink_loss_timeout * 1e6) { /* handle the case where data link was regained, * accept datalink as healthy only after datalink_regain_timeout seconds * */ if (telemetry_lost[i] && - hrt_elapsed_time(&telemetry_last_dl_loss[i]) > datalink_regain_timeout * 1e6) { + hrt_elapsed_time(&telemetry_last_dl_loss[i]) > datalink_regain_timeout * 1e6) { mavlink_log_critical(mavlink_fd, "data link %i regained", i); telemetry_lost[i] = false; have_link = true; + } else if (!telemetry_lost[i]) { /* telemetry was healthy also in last iteration * we don't have to check a timeout */ @@ -1620,6 +1674,7 @@ int commander_thread_main(int argc, char *argv[]) } else { telemetry_last_dl_loss[i] = hrt_absolute_time(); + if (!telemetry_lost[i]) { mavlink_log_critical(mavlink_fd, "data link %i lost", i); telemetry_lost[i] = true; @@ -1647,24 +1702,26 @@ int commander_thread_main(int argc, char *argv[]) * only for fixed wing for now */ if (!status.circuit_breaker_engaged_enginefailure_check && - status.is_rotary_wing == false && - armed.armed && - ((actuator_controls.control[3] > ef_throttle_thres && - battery.current_a/actuator_controls.control[3] < - ef_current2throttle_thres) || - (status.engine_failure))) { + status.is_rotary_wing == false && + armed.armed && + ((actuator_controls.control[3] > ef_throttle_thres && + battery.current_a / actuator_controls.control[3] < + ef_current2throttle_thres) || + (status.engine_failure))) { /* potential failure, measure time */ if (timestamp_engine_healthy > 0 && - hrt_elapsed_time(×tamp_engine_healthy) > - ef_time_thres * 1e6 && - !status.engine_failure) { - status.engine_failure = true; - status_changed = true; - mavlink_log_critical(mavlink_fd, "Engine Failure"); + hrt_elapsed_time(×tamp_engine_healthy) > + ef_time_thres * 1e6 && + !status.engine_failure) { + status.engine_failure = true; + status_changed = true; + mavlink_log_critical(mavlink_fd, "Engine Failure"); } + } else { /* no failure reset flag */ timestamp_engine_healthy = hrt_absolute_time(); + if (status.engine_failure) { status.engine_failure = false; status_changed = true; @@ -1691,20 +1748,22 @@ int commander_thread_main(int argc, char *argv[]) * If we are not in a manual (RC stick controlled mode) * and both failed we want to terminate the flight */ if (status.main_state != MAIN_STATE_MANUAL && - status.main_state != MAIN_STATE_ACRO && - status.main_state != MAIN_STATE_ALTCTL && - status.main_state != MAIN_STATE_POSCTL && - ((status.data_link_lost && status.gps_failure) || - (status.data_link_lost_cmd && status.gps_failure_cmd))) { + status.main_state != MAIN_STATE_ACRO && + status.main_state != MAIN_STATE_ALTCTL && + status.main_state != MAIN_STATE_POSCTL && + ((status.data_link_lost && status.gps_failure) || + (status.data_link_lost_cmd && status.gps_failure_cmd))) { armed.force_failsafe = true; status_changed = true; static bool flight_termination_printed = false; + if (!flight_termination_printed) { warnx("Flight termination because of data link loss && gps failure"); mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination"); flight_termination_printed = true; } - if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 ) { + + if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { mavlink_log_critical(mavlink_fd, "DL and GPS lost: flight termination"); } } @@ -1713,19 +1772,21 @@ int commander_thread_main(int argc, char *argv[]) * If we are in manual (controlled with RC): * if both failed we want to terminate the flight */ if ((status.main_state == MAIN_STATE_ACRO || - status.main_state == MAIN_STATE_MANUAL || - status.main_state == MAIN_STATE_ALTCTL || - status.main_state == MAIN_STATE_POSCTL) && - ((status.rc_signal_lost && status.gps_failure) || - (status.rc_signal_lost_cmd && status.gps_failure_cmd))) { + status.main_state == MAIN_STATE_MANUAL || + status.main_state == MAIN_STATE_ALTCTL || + status.main_state == MAIN_STATE_POSCTL) && + ((status.rc_signal_lost && status.gps_failure) || + (status.rc_signal_lost_cmd && status.gps_failure_cmd))) { armed.force_failsafe = true; status_changed = true; static bool flight_termination_printed = false; + if (!flight_termination_printed) { warnx("Flight termination because of RC signal loss && gps failure"); flight_termination_printed = true; } - if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0 ) { + + if (counter % (1000000 / COMMANDER_MONITORING_INTERVAL) == 0) { mavlink_log_critical(mavlink_fd, "RC and GPS lost: flight termination"); } } @@ -1766,6 +1827,7 @@ int commander_thread_main(int argc, char *argv[]) /* mark home position as set */ status.condition_home_position_valid = true; } + arming_state_changed = false; } @@ -1810,7 +1872,8 @@ int commander_thread_main(int argc, char *argv[]) } /* play arming and battery warning tunes */ - if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available && safety.safety_off))) { + if (!arm_tune_played && armed.armed && (!safety.safety_switch_available || (safety.safety_switch_available + && safety.safety_off))) { /* play tune when armed */ set_tune(TONE_ARMING_WARNING_TUNE); arm_tune_played = true; @@ -1988,6 +2051,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s /* offboard switch overrides main switch */ if (sp_man->offboard_switch == SWITCH_POS_ON) { res = main_state_transition(status_local, MAIN_STATE_OFFBOARD); + if (res == TRANSITION_DENIED) { print_reject_mode(status_local, "OFFBOARD"); @@ -2009,6 +2073,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s } else { res = main_state_transition(status_local, MAIN_STATE_MANUAL); } + // TRANSITION_DENIED is not possible here break; @@ -2023,7 +2088,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s print_reject_mode(status_local, "POSCTL"); } - // fallback to ALTCTL + // fallback to ALTCTL res = main_state_transition(status_local, MAIN_STATE_ALTCTL); if (res != TRANSITION_DENIED) { @@ -2047,14 +2112,14 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s break; // changed successfully or already in this state } - print_reject_mode(status_local, "AUTO_RTL"); + print_reject_mode(status_local, "AUTO_RTL"); - // fallback to LOITER if home position not set - res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); + // fallback to LOITER if home position not set + res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } + if (res != TRANSITION_DENIED) { + break; // changed successfully or already in this state + } } else if (sp_man->loiter_switch == SWITCH_POS_ON) { res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); @@ -2063,7 +2128,7 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s break; // changed successfully or already in this state } - print_reject_mode(status_local, "AUTO_LOITER"); + print_reject_mode(status_local, "AUTO_LOITER"); } else { res = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION); @@ -2072,22 +2137,22 @@ set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_s break; // changed successfully or already in this state } - print_reject_mode(status_local, "AUTO_MISSION"); + print_reject_mode(status_local, "AUTO_MISSION"); - // fallback to LOITER if home position not set - res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); + // fallback to LOITER if home position not set + res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } + if (res != TRANSITION_DENIED) { + break; // changed successfully or already in this state + } } - // fallback to POSCTL - res = main_state_transition(status_local, MAIN_STATE_POSCTL); + // fallback to POSCTL + res = main_state_transition(status_local, MAIN_STATE_POSCTL); - if (res != TRANSITION_DENIED) { - break; // changed successfully or already in this state - } + if (res != TRANSITION_DENIED) { + break; // changed successfully or already in this state + } // fallback to ALTCTL res = main_state_transition(status_local, MAIN_STATE_ALTCTL); @@ -2169,6 +2234,7 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = true; @@ -2177,6 +2243,7 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; + case OFFBOARD_CONTROL_MODE_DIRECT_FORCE: control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = false; @@ -2186,6 +2253,7 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; + case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED: case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED: case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED: @@ -2198,6 +2266,7 @@ set_control_mode() control_mode.flag_control_velocity_enabled = true; //XXX: the flags could depend on sp_offboard.ignore break; + default: control_mode.flag_control_rates_enabled = false; control_mode.flag_control_attitude_enabled = false; @@ -2206,6 +2275,7 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; } + break; case NAVIGATION_STATE_POSCTL: @@ -2415,7 +2485,8 @@ void *commander_low_prio_loop(void *arg) int calib_ret = ERROR; /* try to go to INIT/PREFLIGHT arming state */ - if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, true /* fRunPreArmChecks */, mavlink_fd)) { + if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, + true /* fRunPreArmChecks */, mavlink_fd)) { answer_command(cmd, VEHICLE_CMD_RESULT_DENIED); break; } -- cgit v1.2.3 From 33dcb687e82ea5e0f6bdba37419361ca923703df Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 24 Oct 2014 08:53:10 +0200 Subject: Made some space for FDs - needs proper fix, but will give hackers some relief --- src/modules/sdlog2/sdlog2.c | 23 +++++++++++++++++++---- 1 file changed, 19 insertions(+), 4 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 1282bc0ea..9bde37432 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1038,7 +1038,6 @@ int sdlog2_thread_main(int argc, char *argv[]) subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); subs.status_sub = orb_subscribe(ORB_ID(vehicle_status)); subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); - subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info)); subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); @@ -1057,9 +1056,6 @@ int sdlog2_thread_main(int argc, char *argv[]) subs.esc_sub = orb_subscribe(ORB_ID(esc_status)); subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint)); subs.battery_sub = orb_subscribe(ORB_ID(battery_status)); - for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { - subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]); - } subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder)); subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status)); subs.tecs_status_sub = orb_subscribe(ORB_ID(tecs_status)); @@ -1069,6 +1065,25 @@ int sdlog2_thread_main(int argc, char *argv[]) /* we need to rate-limit wind, as we do not need the full update rate */ orb_set_interval(subs.wind_sub, 90); + + /* add new topics HERE */ + + + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]); + } + + if (_extended_logging) { + subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info)); + } + + /* close non-needed fd's */ + + /* close stdin */ + close(0); + /* close stdout */ + close(1); + thread_running = true; /* initialize thread synchronization */ -- cgit v1.2.3 From cb79ef4df3c7514fa279f3b3259fb0ddc05f3b12 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 24 Oct 2014 15:27:43 +1100 Subject: ll40ls: auto-detect ll40ls on either 0x42 or 0x62 I2C address --- src/drivers/ll40ls/ll40ls.cpp | 53 +++++++++++++++++++++++++++++++++++++++---- 1 file changed, 49 insertions(+), 4 deletions(-) diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp index 8b156f7ba..ce0363dbb 100644 --- a/src/drivers/ll40ls/ll40ls.cpp +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -73,15 +73,19 @@ /* Configuration Constants */ #define LL40LS_BUS PX4_I2C_BUS_EXPANSION -#define LL40LS_BASEADDR 0x42 /* 7-bit address */ +#define LL40LS_BASEADDR 0x62 /* 7-bit address */ +#define LL40LS_BASEADDR_OLD 0x42 /* previous 7-bit address */ #define LL40LS_DEVICE_PATH_INT "/dev/ll40ls_int" #define LL40LS_DEVICE_PATH_EXT "/dev/ll40ls_ext" /* LL40LS Registers addresses */ #define LL40LS_MEASURE_REG 0x00 /* Measure range register */ -#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */ +#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */ #define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */ +#define LL40LS_WHO_AM_I_REG 0x11 +#define LL40LS_WHO_AM_I_REG_VAL 0xCA +#define LL40LS_SIGNAL_STRENGTH_REG 0x5b /* Device limits */ #define LL40LS_MIN_DISTANCE (0.00f) @@ -117,6 +121,7 @@ public: protected: virtual int probe(); + virtual int read_reg(uint8_t reg, uint8_t &val); private: float _min_distance; @@ -210,7 +215,7 @@ LL40LS::LL40LS(int bus, const char *path, int address) : _bus(bus) { // up the retries since the device misses the first measure attempts - I2C::_retries = 3; + _retries = 3; // enable debug() calls _debug_enabled = false; @@ -277,10 +282,50 @@ out: return ret; } +int +LL40LS::read_reg(uint8_t reg, uint8_t &val) +{ + return transfer(®, 1, &val, 1); +} + int LL40LS::probe() { - return measure(); + // cope with both old and new I2C bus address + const uint8_t addresses[2] = {LL40LS_BASEADDR, LL40LS_BASEADDR_OLD}; + + // more retries for detection + _retries = 10; + + for (uint8_t i=0; i Date: Fri, 24 Oct 2014 15:53:46 +1100 Subject: ll40ls: start a measurement after a probe this ensures register 0 also works --- src/drivers/ll40ls/ll40ls.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp index ce0363dbb..6793acd81 100644 --- a/src/drivers/ll40ls/ll40ls.cpp +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -325,7 +325,9 @@ LL40LS::probe() ok: _retries = 3; - return OK; + + // start a measurement + return measure(); } void -- cgit v1.2.3 From ae29d04ff5dc1d3d9c48b081846f04ad34e44373 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 24 Oct 2014 15:57:47 +1100 Subject: px4flow: try a 22 byte transfer in probe() this allows us to distinguish between a ll40ls and px4flow on I2C address 0x42 --- src/drivers/px4flow/px4flow.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 60ad3c1af..04aba9eae 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -249,6 +249,17 @@ out: int PX4FLOW::probe() { + uint8_t val[22]; + + // to be sure this is not a ll40ls Lidar (which can also be on + // 0x42) we check if a 22 byte transfer works from address + // 0. The ll40ls gives an error for that, whereas the flow + // happily returns some data + if (transfer(nullptr, 0, &val[0], 22) != OK) { + return -EIO; + } + + // that worked, so start a measurement cycle return measure(); } -- cgit v1.2.3 From 1d29093f3da209d0ae48ace66d48dfbe72b0cd48 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 28 Oct 2014 12:53:24 +0100 Subject: Flow driver: auto-format fixes --- src/drivers/px4flow/px4flow.cpp | 172 ++++++++++++++++++++++++---------------- 1 file changed, 102 insertions(+), 70 deletions(-) diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 04aba9eae..6c68636c6 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -76,7 +76,7 @@ #define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION #define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84 //range 0x42 - 0x49 - + /* PX4FLOW Registers addresses */ #define PX4FLOW_REG 0x00 /* Measure Register */ @@ -212,8 +212,9 @@ PX4FLOW::~PX4FLOW() stop(); /* free any existing reports */ - if (_reports != nullptr) + if (_reports != nullptr) { delete _reports; + } } int @@ -222,22 +223,25 @@ PX4FLOW::init() int ret = ERROR; /* do I2C init (and probe) first */ - if (I2C::init() != OK) + if (I2C::init() != OK) { goto out; + } /* allocate basic report buffers */ _reports = new RingBuffer(2, sizeof(struct optical_flow_s)); - if (_reports == nullptr) + if (_reports == nullptr) { goto out; + } /* get a publish handle on the px4flow topic */ struct optical_flow_s zero_report; memset(&zero_report, 0, sizeof(zero_report)); _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report); - if (_px4flow_topic < 0) + if (_px4flow_topic < 0) { debug("failed to create px4flow object. Did you start uOrb?"); + } ret = OK; /* sensor is ok, but we don't really know if it is within range */ @@ -258,7 +262,7 @@ PX4FLOW::probe() if (transfer(nullptr, 0, &val[0], 22) != OK) { return -EIO; } - + // that worked, so start a measurement cycle return measure(); } @@ -271,20 +275,20 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg) case SENSORIOCSPOLLRATE: { switch (arg) { - /* switching to manual polling */ + /* switching to manual polling */ case SENSOR_POLLRATE_MANUAL: stop(); _measure_ticks = 0; return OK; - /* external signalling (DRDY) not supported */ + /* external signalling (DRDY) not supported */ case SENSOR_POLLRATE_EXTERNAL: - /* zero would be bad */ + /* zero would be bad */ case 0: return -EINVAL; - /* set default/max polling rate */ + /* set default/max polling rate */ case SENSOR_POLLRATE_MAX: case SENSOR_POLLRATE_DEFAULT: { /* do we need to start internal polling? */ @@ -294,13 +298,14 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg) _measure_ticks = USEC2TICK(PX4FLOW_CONVERSION_INTERVAL); /* if we need to start the poll state machine, do it */ - if (want_start) + if (want_start) { start(); + } return OK; } - /* adjust to a legal polling interval in Hz */ + /* adjust to a legal polling interval in Hz */ default: { /* do we need to start internal polling? */ bool want_start = (_measure_ticks == 0); @@ -309,15 +314,17 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg) unsigned ticks = USEC2TICK(1000000 / arg); /* check against maximum rate */ - if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) + if (ticks < USEC2TICK(PX4FLOW_CONVERSION_INTERVAL)) { return -EINVAL; + } /* update interval for next measurement */ _measure_ticks = ticks; /* if we need to start the poll state machine, do it */ - if (want_start) + if (want_start) { start(); + } return OK; } @@ -325,25 +332,29 @@ PX4FLOW::ioctl(struct file *filp, int cmd, unsigned long arg) } case SENSORIOCGPOLLRATE: - if (_measure_ticks == 0) + if (_measure_ticks == 0) { return SENSOR_POLLRATE_MANUAL; + } return (1000 / _measure_ticks); case SENSORIOCSQUEUEDEPTH: { - /* lower bound is mandatory, upper bound is a sanity check */ - if ((arg < 1) || (arg > 100)) - return -EINVAL; + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 1) || (arg > 100)) { + return -EINVAL; + } + + irqstate_t flags = irqsave(); + + if (!_reports->resize(arg)) { + irqrestore(flags); + return -ENOMEM; + } - irqstate_t flags = irqsave(); - if (!_reports->resize(arg)) { irqrestore(flags); - return -ENOMEM; - } - irqrestore(flags); - return OK; - } + return OK; + } case SENSORIOCGQUEUEDEPTH: return _reports->size(); @@ -366,8 +377,9 @@ PX4FLOW::read(struct file *filp, char *buffer, size_t buflen) int ret = 0; /* buffer must be large enough */ - if (count < 1) + if (count < 1) { return -ENOSPC; + } /* if automatic measurement is enabled */ if (_measure_ticks > 0) { @@ -428,13 +440,13 @@ PX4FLOW::measure() uint8_t cmd = PX4FLOW_REG; ret = transfer(&cmd, 1, nullptr, 0); - if (OK != ret) - { + if (OK != ret) { perf_count(_comms_errors); log("i2c::transfer returned %d", ret); - printf("i2c::transfer flow returned %d"); + printf("i2c::transfer flow returned %d"); return ret; } + ret = OK; return ret; @@ -446,14 +458,13 @@ PX4FLOW::collect() int ret = -EIO; /* read from the sensor */ - uint8_t val[22] = {0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0,0, 0}; + uint8_t val[22] = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; perf_begin(_sample_perf); ret = transfer(nullptr, 0, &val[0], 22); - if (ret < 0) - { + if (ret < 0) { log("error reading from sensor: %d", ret); perf_count(_comms_errors); perf_end(_sample_perf); @@ -478,12 +489,12 @@ PX4FLOW::collect() int16_t gdist = val[21] << 8 | val[20]; struct optical_flow_s report; - report.flow_comp_x_m = float(flowcx)/1000.0f; - report.flow_comp_y_m = float(flowcy)/1000.0f; - report.flow_raw_x= val[3] << 8 | val[2]; - report.flow_raw_y= val[5] << 8 | val[4]; - report.ground_distance_m =float(gdist)/1000.0f; - report.quality= val[10]; + report.flow_comp_x_m = float(flowcx) / 1000.0f; + report.flow_comp_y_m = float(flowcy) / 1000.0f; + report.flow_raw_x = val[3] << 8 | val[2]; + report.flow_raw_y = val[5] << 8 | val[4]; + report.ground_distance_m = float(gdist) / 1000.0f; + report.quality = val[10]; report.sensor_id = 0; report.timestamp = hrt_absolute_time(); @@ -520,11 +531,13 @@ PX4FLOW::start() true, true, true, - SUBSYSTEM_TYPE_OPTICALFLOW}; + SUBSYSTEM_TYPE_OPTICALFLOW + }; 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); } @@ -578,8 +591,9 @@ PX4FLOW::cycle() } /* measurement phase */ - if (OK != measure()) + if (OK != measure()) { log("measure error"); + } /* next phase is collection */ _collect_phase = true; @@ -630,33 +644,37 @@ start() { int fd; - if (g_dev != nullptr) + if (g_dev != nullptr) { errx(1, "already started"); + } /* create the driver */ g_dev = new PX4FLOW(PX4FLOW_BUS); - if (g_dev == nullptr) + if (g_dev == nullptr) { goto fail; + } - if (OK != g_dev->init()) + if (OK != g_dev->init()) { goto fail; + } /* set the poll rate to default, starts automatic data collection */ fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY); - if (fd < 0) + if (fd < 0) { goto fail; + } - if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0) + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MAX) < 0) { goto fail; + } exit(0); fail: - if (g_dev != nullptr) - { + if (g_dev != nullptr) { delete g_dev; g_dev = nullptr; } @@ -669,15 +687,14 @@ fail: */ void stop() { - if (g_dev != nullptr) - { + if (g_dev != nullptr) { delete g_dev; g_dev = nullptr; - } - else - { + + } else { errx(1, "driver not running"); } + exit(0); } @@ -695,14 +712,17 @@ test() int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY); - if (fd < 0) + if (fd < 0) { err(1, "%s open failed (try 'px4flow start' if the driver is not running", PX4FLOW_DEVICE_PATH); + } /* do a simple demand read */ sz = read(fd, &report, sizeof(report)); if (sz != sizeof(report)) - // err(1, "immediate read failed"); + { + warnx("immediate read failed"); + } warnx("single read"); warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m); @@ -711,8 +731,9 @@ test() /* start the sensor polling at 2Hz */ - if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) { errx(1, "failed to set 2Hz poll rate"); + } /* read the sensor 5x and report each value */ for (unsigned i = 0; i < 5; i++) { @@ -723,14 +744,16 @@ test() fds.events = POLLIN; ret = poll(&fds, 1, 2000); - if (ret != 1) + if (ret != 1) { errx(1, "timed out waiting for sensor data"); + } /* now go get it */ sz = read(fd, &report, sizeof(report)); - if (sz != sizeof(report)) + if (sz != sizeof(report)) { err(1, "periodic read failed"); + } warnx("periodic read %u", i); warnx("flowx: %0.2f m/s", (double)report.flow_comp_x_m); @@ -751,14 +774,17 @@ reset() { int fd = open(PX4FLOW_DEVICE_PATH, O_RDONLY); - if (fd < 0) + if (fd < 0) { err(1, "failed "); + } - if (ioctl(fd, SENSORIOCRESET, 0) < 0) + if (ioctl(fd, SENSORIOCRESET, 0) < 0) { err(1, "driver reset failed"); + } - if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { err(1, "driver poll restart failed"); + } exit(0); } @@ -769,8 +795,9 @@ reset() void info() { - if (g_dev == nullptr) + if (g_dev == nullptr) { errx(1, "driver not running"); + } printf("state @ %p\n", g_dev); g_dev->print_info(); @@ -786,32 +813,37 @@ px4flow_main(int argc, char *argv[]) /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) + if (!strcmp(argv[1], "start")) { px4flow::start(); + } - /* - * Stop the driver - */ - if (!strcmp(argv[1], "stop")) - px4flow::stop(); + /* + * Stop the driver + */ + if (!strcmp(argv[1], "stop")) { + px4flow::stop(); + } /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(argv[1], "test")) { px4flow::test(); + } /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(argv[1], "reset")) { px4flow::reset(); + } /* * Print driver information. */ - if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) + if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) { px4flow::info(); + } errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); } -- cgit v1.2.3 From aa7b00f8199e167b94a7c5e9e4e004bbd50b2f68 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 Oct 2014 09:58:44 +0100 Subject: Add define to cull flash-intense mathlib tests --- src/systemcmds/tests/tests_main.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c index e3f26924f..0f56704e6 100644 --- a/src/systemcmds/tests/tests_main.c +++ b/src/systemcmds/tests/tests_main.c @@ -110,7 +110,9 @@ const struct { {"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST}, {"mtd", test_mtd, 0}, +#ifndef TESTS_MATHLIB_DISABLE {"mathlib", test_mathlib, 0}, +#endif {"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST}, {NULL, NULL, 0} }; -- cgit v1.2.3 From a6c6ae023de74f87ee593e8c914d66e7a8be7011 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 Oct 2014 14:04:33 +0100 Subject: Autoformatting (reviewed) IO sbus handler. No functionality changes. --- src/modules/px4iofirmware/sbus.c | 55 ++++++++++++++++++++++++---------------- 1 file changed, 33 insertions(+), 22 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 0f0414148..6ead38d61 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -61,7 +61,7 @@ /* Measured values with Futaba FX-30/R6108SB: -+100% on TX: PCM 1.100/1.520/1.950ms -> SBus raw values: 350/1024/1700 (100% ATV) - -+140% on TX: PCM 0.930/1.520/2.112ms -> SBus raw values: 78/1024/1964 (140% ATV) + -+140% on TX: PCM 0.930/1.520/2.112ms -> SBus raw values: 78/1024/1964 (140% ATV) -+152% on TX: PCM 0.884/1.520/2.160ms -> SBus raw values: 1/1024/2047 (140% ATV plus dirty tricks) */ @@ -87,13 +87,15 @@ static unsigned partial_frame_count; unsigned sbus_frame_drops; -static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels); +static bool sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, + bool *sbus_frame_drop, uint16_t max_channels); int sbus_init(const char *device) { - if (sbus_fd < 0) + if (sbus_fd < 0) { sbus_fd = open(device, O_RDWR | O_NONBLOCK); + } if (sbus_fd >= 0) { struct termios t; @@ -113,6 +115,7 @@ sbus_init(const char *device) } else { debug("S.Bus: open failed"); } + return sbus_fd; } @@ -167,8 +170,9 @@ sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sb ret = read(sbus_fd, &frame[partial_frame_count], SBUS_FRAME_SIZE - partial_frame_count); /* if the read failed for any reason, just give up here */ - if (ret < 1) + if (ret < 1) { return false; + } last_rx_time = now; @@ -180,8 +184,9 @@ sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sb /* * If we don't have a full frame, return */ - if (partial_frame_count < SBUS_FRAME_SIZE) + if (partial_frame_count < SBUS_FRAME_SIZE) { return false; + } /* * Great, it looks like we might have a frame. Go ahead and @@ -228,7 +233,8 @@ static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = { }; static bool -sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values) +sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, + uint16_t max_values) { /* check frame boundary markers to avoid out-of-sync cases */ if ((frame[0] != 0x0f)) { @@ -237,23 +243,27 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool } switch (frame[24]) { - case 0x00: + case 0x00: /* this is S.BUS 1 */ break; - case 0x03: + + case 0x03: /* S.BUS 2 SLOT0: RX battery and external voltage */ break; - case 0x83: + + case 0x83: /* S.BUS 2 SLOT1 */ break; - case 0x43: - case 0xC3: - case 0x23: - case 0xA3: - case 0x63: - case 0xE3: + + case 0x43: + case 0xC3: + case 0x23: + case 0xA3: + case 0x63: + case 0xE3: break; - default: + + default: /* we expect one of the bits above, but there are some we don't know yet */ break; } @@ -283,7 +293,7 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */ - values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET; + values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR + .5f) + SBUS_SCALE_OFFSET; } /* decode switch channels if data fields are wide enough */ @@ -304,16 +314,17 @@ sbus_decode(hrt_abstime frame_time, uint16_t *values, uint16_t *num_values, bool /* report that we failed to read anything valid off the receiver */ *sbus_failsafe = true; *sbus_frame_drop = true; - } - else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ + + } else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */ /* set a special warning flag - * - * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this - * condition as fail-safe greatly reduces the reliability and range of the radio link, + * + * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this + * condition as fail-safe greatly reduces the reliability and range of the radio link, * e.g. by prematurely issueing return-to-launch!!! */ *sbus_failsafe = false; *sbus_frame_drop = true; + } else { *sbus_failsafe = false; *sbus_frame_drop = false; -- cgit v1.2.3 From 4839ed915c68ffc60700fe170e5ba3766a6b34f1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 Oct 2014 17:00:00 +0100 Subject: Update MAVLink submodule --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 8587a007c..76a9dd756 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 8587a007cf89cb13f146ac46be94b61276343ce1 +Subproject commit 76a9dd75632ecf0f622b8b0af098fa51033796a7 -- cgit v1.2.3 From d5b8385a13f4d09453bc00406ec96da9345addcf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 29 Oct 2014 17:55:53 +0100 Subject: Fix low stack space on commander - relevant in HIL --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index cb507c9ba..b72ebcc50 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -263,7 +263,7 @@ int commander_main(int argc, char *argv[]) daemon_task = task_spawn_cmd("commander", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 2950, + 3200, commander_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); -- cgit v1.2.3 From 2e33683630002aef5881734c96383685b7e8443f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 27 Oct 2014 13:10:58 +0100 Subject: Abort on large packets which do not fit in buffer - not just if the gap is not provided any more. --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0d932d20a..4448f8d6f 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -763,7 +763,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) _last_write_try_time = hrt_absolute_time(); /* check if there is space in the buffer, let it overflow else */ - if (buf_free < TX_BUFFER_GAP) { + if ((buf_free < TX_BUFFER_GAP) || (buf_free < packet_len)) { /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); -- cgit v1.2.3 From dd23d0acbcce9f4c79e120ec782a522164a25d83 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 9 Oct 2014 15:35:18 +1100 Subject: drivers: allow forcing the safety switch on This allows forcing the safety switch to the on position from software which stops the pwm outputs --- src/drivers/drv_pwm_output.h | 3 +++ src/drivers/px4fmu/fmu.cpp | 1 + src/drivers/px4io/px4io.cpp | 5 +++++ src/modules/px4iofirmware/protocol.h | 1 + src/modules/px4iofirmware/registers.c | 6 ++++++ 5 files changed, 16 insertions(+) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index f66ec7c95..6873f24b6 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -213,6 +213,9 @@ ORB_DECLARE(output_pwm); /** make failsafe non-recoverable (termination) if it occurs */ #define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25) +/** force safety switch on (to enable use of safety switch) */ +#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26) + /* * * diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 122a3cd17..3d3e1b0eb 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -829,6 +829,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) case PWM_SERVO_SET_ARM_OK: case PWM_SERVO_CLEAR_ARM_OK: case PWM_SERVO_SET_FORCE_SAFETY_OFF: + case PWM_SERVO_SET_FORCE_SAFETY_ON: // these are no-ops, as no safety switch break; diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 3871b4a2c..fd9eb4170 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2278,6 +2278,11 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg) ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC); break; + case PWM_SERVO_SET_FORCE_SAFETY_ON: + /* force safety switch on */ + ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_ON, PX4IO_FORCE_SAFETY_MAGIC); + break; + case PWM_SERVO_SET_FORCE_FAILSAFE: /* force failsafe mode instantly */ if (arg == 0) { diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index a3e8a58d3..9b2e047cb 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -221,6 +221,7 @@ enum { /* DSM bind states */ hence index 12 can safely be used. */ #define PX4IO_P_SETUP_RC_THR_FAILSAFE_US 13 /**< the throttle failsafe pulse length in microseconds */ +#define PX4IO_P_SETUP_FORCE_SAFETY_ON 14 /* force safety switch into 'disarmed' (PWM disabled state) */ #define PX4IO_FORCE_SAFETY_MAGIC 22027 /* required argument for force safety (random) */ /* autopilot control values, -10000..10000 */ diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 7f19e983f..49c2a9f56 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -603,6 +603,12 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) dsm_bind(value & 0x0f, (value >> 4) & 0xF); break; + case PX4IO_P_SETUP_FORCE_SAFETY_ON: + if (value == PX4IO_FORCE_SAFETY_MAGIC) { + r_status_flags &= ~PX4IO_P_STATUS_FLAGS_SAFETY_OFF; + } + break; + case PX4IO_P_SETUP_FORCE_SAFETY_OFF: if (value == PX4IO_FORCE_SAFETY_MAGIC) { r_status_flags |= PX4IO_P_STATUS_FLAGS_SAFETY_OFF; -- cgit v1.2.3 From c396a6774626a6a993030c910697873e6b1b1195 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 16 Dec 2013 22:15:37 +1100 Subject: mpu6000: added logging of good transfers this helps tracking down a startup issue --- src/drivers/mpu6000/mpu6000.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index b22bb2e07..a95e041a1 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -229,6 +229,7 @@ private: perf_counter_t _gyro_reads; perf_counter_t _sample_perf; perf_counter_t _bad_transfers; + perf_counter_t _good_transfers; math::LowPassFilter2p _accel_filter_x; math::LowPassFilter2p _accel_filter_y; @@ -404,6 +405,7 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev _gyro_reads(perf_alloc(PC_COUNT, "mpu6000_gyro_read")), _sample_perf(perf_alloc(PC_ELAPSED, "mpu6000_read")), _bad_transfers(perf_alloc(PC_COUNT, "mpu6000_bad_transfers")), + _good_transfers(perf_alloc(PC_COUNT, "mpu6000_good_transfers")), _accel_filter_x(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), _accel_filter_y(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), _accel_filter_z(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), @@ -456,6 +458,7 @@ MPU6000::~MPU6000() perf_free(_accel_reads); perf_free(_gyro_reads); perf_free(_bad_transfers); + perf_free(_good_transfers); } int @@ -1279,8 +1282,14 @@ MPU6000::measure() // all zero data - probably a SPI bus error perf_count(_bad_transfers); perf_end(_sample_perf); + // note that we don't call reset() here as a reset() + // costs 20ms with interrupts disabled. That means if + // the mpu6k does go bad it would cause a FMU failure, + // regardless of whether another sensor is available, return; } + + perf_count(_good_transfers); /* @@ -1399,6 +1408,8 @@ MPU6000::print_info() perf_print_counter(_sample_perf); perf_print_counter(_accel_reads); perf_print_counter(_gyro_reads); + perf_print_counter(_bad_transfers); + perf_print_counter(_good_transfers); _accel_reports->print_info("accel queue"); _gyro_reports->print_info("gyro queue"); } -- cgit v1.2.3 From 47367aeed526e7ca72e9cb7290e745dc0e6e2061 Mon Sep 17 00:00:00 2001 From: philipoe Date: Wed, 29 Oct 2014 15:56:31 +0100 Subject: TECS: Fix bug (underspeed-condition did not have any effect on throttle) --- src/lib/external_lgpl/tecs/tecs.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 6a2a61b04..0ed210cf4 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -299,7 +299,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM // Calculate throttle demand // If underspeed condition is set, then demand full throttle if (_underspeed) { - _throttle_dem_unc = 1.0f; + _throttle_dem = 1.0f; } else { // Calculate gain scaler from specific energy error to throttle @@ -363,10 +363,10 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM } else { _throttle_dem = ff_throttle; } - } - // Constrain throttle demand - _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf); + // Constrain throttle demand + _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf); + } } void TECS::_detect_bad_descent(void) -- cgit v1.2.3 From a82f4881c7f0dee36860ca69fef1e63b0d863b8c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 11 Oct 2014 06:14:16 +1100 Subject: sdlog2_dump: Fixing incorrect tabbing to allow for CSV generation --- Tools/sdlog2/sdlog2_dump.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) mode change 100644 => 100755 Tools/sdlog2/sdlog2_dump.py diff --git a/Tools/sdlog2/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py old mode 100644 new mode 100755 index ca2efb021..8b0ccb2d7 --- a/Tools/sdlog2/sdlog2_dump.py +++ b/Tools/sdlog2/sdlog2_dump.py @@ -154,8 +154,8 @@ class SDLog2Parser: first_data_msg = False self.__parseMsg(msg_descr) bytes_read += self.__ptr - if not self.__debug_out and self.__time_msg != None and self.__csv_updated: - self.__printCSVRow() + if not self.__debug_out and self.__time_msg != None and self.__csv_updated: + self.__printCSVRow() f.close() def __bytesLeft(self): -- cgit v1.2.3 From 02e35991d52f280d978c3ddd527269b1f9fd176d Mon Sep 17 00:00:00 2001 From: philipoe Date: Thu, 30 Oct 2014 09:54:27 +0100 Subject: TECS: Also deleted the _throttle_dem_unc variable from TECS.h --- src/lib/external_lgpl/tecs/tecs.h | 3 --- 1 file changed, 3 deletions(-) diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h index 8ac31de6f..eb45237b7 100644 --- a/src/lib/external_lgpl/tecs/tecs.h +++ b/src/lib/external_lgpl/tecs/tecs.h @@ -345,9 +345,6 @@ private: // climbout mode bool _climbOutDem; - // throttle demand before limiting - float _throttle_dem_unc; - // pitch demand before limiting float _pitch_dem_unc; -- cgit v1.2.3 From d0d2c7f9c69c5cfdd3aabf757796d2d6ada32875 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 30 Oct 2014 15:10:44 +0100 Subject: Updated MAVLink revision --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 76a9dd756..90383fac8 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 76a9dd75632ecf0f622b8b0af098fa51033796a7 +Subproject commit 90383fac84d031aef17989a1497c2473dfa64340 -- cgit v1.2.3 From 2f715b74dd4866945e7ebe6aab735cd1e58fe01d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 30 Oct 2014 15:36:16 +0100 Subject: Fix build breakage on mavlink update --- src/modules/mavlink/mavlink_receiver.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index e8d783847..9247f999a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -391,11 +391,9 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) f.timestamp = hrt_absolute_time(); f.flow_timestamp = flow.time_usec; - f.flow_raw_x = flow.flow_x; - f.flow_raw_y = flow.flow_y; - f.flow_comp_x_m = flow.flow_comp_m_x; - f.flow_comp_y_m = flow.flow_comp_m_y; - f.ground_distance_m = flow.ground_distance; + f.flow_raw_x = flow.integrated_x; + f.flow_raw_y = flow.integrated_y; + f.ground_distance_m = flow.distance; f.quality = flow.quality; f.sensor_id = flow.sensor_id; @@ -413,7 +411,7 @@ MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg) r.timestamp = hrt_absolute_time(); r.error_count = 0; r.type = RANGE_FINDER_TYPE_LASER; - r.distance = flow.ground_distance; + r.distance = flow.distance; r.minimum_distance = 0.0f; r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance); -- cgit v1.2.3 From 9f3c3529593033d9acc94fb978a2aa6e34a3d1d9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 30 Oct 2014 16:38:27 +0100 Subject: Leave NSH terminal enough stack space --- src/systemcmds/nshterm/module.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk index 7d2c59f91..41706e137 100644 --- a/src/systemcmds/nshterm/module.mk +++ b/src/systemcmds/nshterm/module.mk @@ -38,6 +38,6 @@ MODULE_COMMAND = nshterm SRCS = nshterm.c -MODULE_STACKSIZE = 1400 +MODULE_STACKSIZE = 1600 MAXOPTIMIZATION = -Os -- cgit v1.2.3 From c7a3a0db5230d1506c81c5f15254002b64cddf32 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 31 Oct 2014 08:58:58 +0100 Subject: Don't go into an error state if we are temporarily powering via USB on the bench --- 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 b72ebcc50..46caddd46 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1407,8 +1407,8 @@ int commander_thread_main(int argc, char *argv[]) last_idle_time = system_load.tasks[0].total_runtime; /* check if board is connected via USB */ - //struct stat statbuf; - //on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0); + struct stat statbuf; + on_usb_power = (stat("/dev/ttyACM0", &statbuf) == 0); } /* if battery voltage is getting lower, warn using buzzer, etc. */ @@ -1418,7 +1418,7 @@ int commander_thread_main(int argc, char *argv[]) status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; - } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.09f + } else if (!on_usb_power && status.condition_battery_voltage_valid && status.battery_remaining < 0.09f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; -- cgit v1.2.3 From eeda1886f0e7f15b2e51d863020f794b1a84efc1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Nov 2014 11:07:36 +0100 Subject: Simplify error messages for NSH term --- src/systemcmds/nshterm/nshterm.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index fca1798e6..f06c49552 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -87,7 +87,7 @@ nshterm_main(int argc, char *argv[]) /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(fd, &uart_config)) < 0) { - warnx("ERROR get termios config %s: %d\n", argv[1], termios_state); + warnx("ERR get config %s: %d\n", argv[1], termios_state); close(fd); return -1; } @@ -96,7 +96,7 @@ nshterm_main(int argc, char *argv[]) uart_config.c_oflag |= (ONLCR | OPOST/* | OCRNL*/); if ((termios_state = tcsetattr(fd, TCSANOW, &uart_config)) < 0) { - warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", argv[1]); + warnx("ERR set config %s\n", argv[1]); close(fd); return -1; } -- cgit v1.2.3 From 83eb81251c8405c96aaa72fc1634d15a5b54af29 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Nov 2014 11:22:18 +0100 Subject: NSH term: Only time out if no arming information is available, if arming information is available abort if unconnected on arming --- src/systemcmds/nshterm/nshterm.c | 27 +++++++++++++++++++++++++-- 1 file changed, 25 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index f06c49552..edeb5c624 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -51,6 +51,8 @@ #include #include +#include + __EXPORT int nshterm_main(int argc, char *argv[]); int @@ -62,9 +64,30 @@ nshterm_main(int argc, char *argv[]) } unsigned retries = 0; int fd = -1; + int armed_fd = orb_subscribe(ORB_ID(actuator_armed)); + struct actuator_armed_s armed; + /* we assume the system does not provide arming status feedback */ + bool armed_updated = false; + + /* try the first 30 seconds or if arming system is ready */ + while ((retries < 300) || armed_updated) { + + /* abort if an arming topic is published and system is armed */ + bool updated = false; + if (orb_check(armed_fd, &updated)) { + /* the system is now providing arming status feedback. + * instead of timing out, we resort to abort bringing + * up the terminal. + */ + armed_updated = true; + orb_copy(ORB_ID(actuator_armed), armed_fd, &armed); + + if (armed.armed) { + /* this is not an error, but we are done */ + exit(0); + } + } - /* try the first 30 seconds */ - while (retries < 300) { /* the retries are to cope with the behaviour of /dev/ttyACM0 */ /* which may not be ready immediately. */ fd = open(argv[1], O_RDWR); -- cgit v1.2.3 From c442f820dd89aad9fac394ce56c07b10cfcacf73 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Nov 2014 16:54:11 +0100 Subject: Encode RC type in RSSI field for GCS --- src/modules/mavlink/mavlink_messages.cpp | 43 +++++++++++++++++++++++++++++++- 1 file changed, 42 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index cccb698bf..87858690f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1717,7 +1717,48 @@ protected: msg.chan16_raw = (rc.channel_count > 15) ? rc.values[15] : UINT16_MAX; msg.chan17_raw = (rc.channel_count > 16) ? rc.values[16] : UINT16_MAX; msg.chan18_raw = (rc.channel_count > 17) ? rc.values[17] : UINT16_MAX; - msg.rssi = rc.rssi; + + /* RSSI has a max value of 100, and when Spektrum or S.BUS are + * available, the RSSI field is invalid, as they do not provide + * an RSSI measurement. Use an out of band magic value to signal + * these digital ports. XXX revise MAVLink spec to address this. + * One option would be to use the top bit to toggle between RSSI + * and input source mode. + * + * Full RSSI field: 0b 1 111 1111 + * + * ^ If bit is set, RSSI encodes type + RSSI + * + * ^ These three bits encode a total of 8 + * digital RC input types. + * 0: PPM, 1: SBUS, 2: Spektrum, 2: ST24 + * ^ These four bits encode a total of + * 16 RSSI levels. 15 = full, 0 = no signal + * + */ + + /* Initialize RSSI with the special mode level flag */ + msg.rssi = (1 << 7); + + /* Set RSSI */ + msg.rssi |= (rc.rssi <= 100) ? ((rc.rssi / 7) + 1) : 15; + + switch (rc.input_source) { + case RC_INPUT_SOURCE_PX4FMU_PPM: + /* fallthrough */ + case RC_INPUT_SOURCE_PX4IO_PPM: + msg.rssi |= (0 << 4); + break; + case RC_INPUT_SOURCE_PX4IO_SPEKTRUM: + msg.rssi |= (1 << 4); + break; + case RC_INPUT_SOURCE_PX4IO_SBUS: + msg.rssi |= (2 << 4); + break; + case RC_INPUT_SOURCE_PX4IO_ST24: + msg.rssi |= (3 << 4); + break; + } _mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS, &msg); } -- cgit v1.2.3 From 412ddde5dca055ba090ed2e18db2dc77b6af93a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 1 Nov 2014 16:58:12 +0100 Subject: Force RSSI to zero if RC is lost --- src/modules/mavlink/mavlink_messages.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 87858690f..a2b3cc62e 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1760,6 +1760,11 @@ protected: break; } + if (rc.rc_lost) { + /* RSSI is by definition zero */ + msg.rssi = 0; + } + _mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS, &msg); } } -- cgit v1.2.3 From 2cadd45f307750bb68c3f926d7d9830f680bd94b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 10:13:11 +0100 Subject: Configure led ring and enable heartbeat on it --- src/drivers/boards/px4io-v2/board_config.h | 1 + src/drivers/boards/px4io-v2/px4iov2_init.c | 1 + src/modules/px4iofirmware/px4io.c | 2 ++ src/modules/px4iofirmware/px4io.h | 1 + 4 files changed, 5 insertions(+) diff --git a/src/drivers/boards/px4io-v2/board_config.h b/src/drivers/boards/px4io-v2/board_config.h index ef9bb5cad..10a93be0b 100644 --- a/src/drivers/boards/px4io-v2/board_config.h +++ b/src/drivers/boards/px4io-v2/board_config.h @@ -77,6 +77,7 @@ #define GPIO_LED1 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN14) #define GPIO_LED2 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN15) #define GPIO_LED3 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN13) +#define GPIO_LED4 (GPIO_OUTPUT|GPIO_CNF_OUTOD|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN11) /* Safety switch button *******************************************************/ diff --git a/src/drivers/boards/px4io-v2/px4iov2_init.c b/src/drivers/boards/px4io-v2/px4iov2_init.c index 9f8c0eeb2..5c3343ccc 100644 --- a/src/drivers/boards/px4io-v2/px4iov2_init.c +++ b/src/drivers/boards/px4io-v2/px4iov2_init.c @@ -108,6 +108,7 @@ __EXPORT void stm32_boardinitialize(void) stm32_configgpio(GPIO_LED1); stm32_configgpio(GPIO_LED2); stm32_configgpio(GPIO_LED3); + stm32_configgpio(GPIO_LED4); stm32_configgpio(GPIO_BTN_SAFETY); diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index cd134ccb4..f978ff406 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -124,6 +124,7 @@ heartbeat_blink(void) { static bool heartbeat = false; LED_BLUE(heartbeat = !heartbeat); + LED_RING(heartbeat); } static uint64_t reboot_time; @@ -191,6 +192,7 @@ user_start(int argc, char *argv[]) LED_AMBER(false); LED_BLUE(false); LED_SAFETY(false); + LED_RING(false); /* turn on servo power (if supported) */ #ifdef POWER_SERVO diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index e32fcc72b..8186e4c78 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -140,6 +140,7 @@ extern pwm_limit_t pwm_limit; #define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED1, !(_s)) #define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s)) #define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s)) +#define LED_RING(_s) stm32_gpiowrite(GPIO_LED4, !(_s)) #ifdef CONFIG_ARCH_BOARD_PX4IO_V1 -- cgit v1.2.3 From 75d0ffe4e5b7659e20bbbdcc1e840e06dfe7a138 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 12:34:33 +0100 Subject: Build fix --- src/modules/px4iofirmware/px4io.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index f978ff406..30f32b38e 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -124,7 +124,9 @@ heartbeat_blink(void) { static bool heartbeat = false; LED_BLUE(heartbeat = !heartbeat); +#ifdef GPIO_LED4 LED_RING(heartbeat); +#endif } static uint64_t reboot_time; @@ -192,7 +194,9 @@ user_start(int argc, char *argv[]) LED_AMBER(false); LED_BLUE(false); LED_SAFETY(false); +#ifdef GPIO_LED4 LED_RING(false); +#endif /* turn on servo power (if supported) */ #ifdef POWER_SERVO -- cgit v1.2.3 From ce1ec430f89e2080ad053115459bf91dd6585d3a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 12:58:32 +0100 Subject: Ensure MAVLink app has enough stack space --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 4448f8d6f..6b4edff78 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1634,7 +1634,7 @@ Mavlink::start(int argc, char *argv[]) task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2700, + 2900, (main_t)&Mavlink::start_helper, (const char **)argv); -- cgit v1.2.3 From acb739655d5c2ebf50449842ae2b7b9b7c76dbd1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 17:06:35 +0100 Subject: Remove huge memory overhead in RC channels topic, was completely unnecessary --- src/modules/uORB/topics/rc_channels.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h index 8978de471..b14ae1edd 100644 --- a/src/modules/uORB/topics/rc_channels.h +++ b/src/modules/uORB/topics/rc_channels.h @@ -76,7 +76,6 @@ struct rc_channels_s { uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */ float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */ uint8_t channel_count; /**< Number of valid channels */ - char function_name[RC_CHANNELS_FUNCTION_MAX][20]; /**< String array to store the names of the functions */ int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */ uint8_t rssi; /**< Receive signal strength index */ bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */ -- cgit v1.2.3 From baba157785ee1298e70fb358a0ffe76f18fc3b54 Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sat, 1 Nov 2014 18:45:40 -0400 Subject: Encoder logging support. --- src/modules/sdlog2/sdlog2.c | 16 +++++++++++++++- src/modules/sdlog2/sdlog2_messages.h | 11 +++++++++++ 2 files changed, 26 insertions(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 9bde37432..1820fc104 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -90,6 +90,7 @@ #include #include #include +#include #include #include @@ -954,6 +955,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct servorail_status_s servorail_status; struct satellite_info_s sat_info; struct wind_estimate_s wind_estimate; + struct encoders_s encoders; } buf; memset(&buf, 0, sizeof(buf)); @@ -996,6 +998,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_GS1B_s log_GS1B; struct log_TECS_s log_TECS; struct log_WIND_s log_WIND; + struct log_ENCODERS_s log_ENCODERS; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -1033,6 +1036,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int system_power_sub; int servorail_status_sub; int wind_sub; + int encoders_sub; } subs; subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); @@ -1064,7 +1068,7 @@ int sdlog2_thread_main(int argc, char *argv[]) subs.wind_sub = orb_subscribe(ORB_ID(wind_estimate)); /* we need to rate-limit wind, as we do not need the full update rate */ orb_set_interval(subs.wind_sub, 90); - + subs.encoders_sub = orb_subscribe(ORB_ID(encoders)); /* add new topics HERE */ @@ -1667,6 +1671,16 @@ int sdlog2_thread_main(int argc, char *argv[]) LOGBUFFER_WRITE_AND_COUNT(WIND); } + /* --- ENCODERS --- */ + if (copy_if_updated(ORB_ID(encoders), subs.encoders_sub, &buf.encoders)) { + log_msg.msg_type = LOG_ENCODERS_MSG; + log_msg.body.log_ENCODERS.counts_0 = buf.encoders.counts[0]; + log_msg.body.log_ENCODERS.velocity_0 = buf.encoders.velocity[0]; + log_msg.body.log_ENCODERS.counts_1 = buf.encoders.counts[1]; + log_msg.body.log_ENCODERS.velocity_1 = buf.encoders.velocity[1]; + LOGBUFFER_WRITE_AND_COUNT(ENCODERS); + } + /* 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 d49fc0c79..7fd07809d 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -407,6 +407,16 @@ struct log_VISN_s { float qw; }; +/* --- ENCODERS - ENCODER DATA --- */ +#define LOG_ENCODERS_MSG 39 +struct log_ENCODERS_s { + int64_t counts_0; + float velocity_0; + int64_t counts_1; + float velocity_1; +}; + + /********** SYSTEM MESSAGES, ID > 0x80 **********/ /* --- TIME - TIME STAMP --- */ @@ -471,6 +481,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(TECS, "fffffffffffffB", "ASP,AF,FSP,F,FF,AsSP,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"), + LOG_FORMAT(ENCODERS, "qfqf", "counts_0, velocity_0, counts_1, velocity_1"), /* system-level messages, ID >= 0x80 */ /* FMT: don't write format of format message, it's useless */ -- cgit v1.2.3 From 0e5b91d16fd35b1ad78df1a772ceb23676e5fa7a Mon Sep 17 00:00:00 2001 From: James Goppert Date: Sun, 2 Nov 2014 14:22:23 -0500 Subject: Shortened encoder logging names. --- src/modules/sdlog2/sdlog2.c | 14 +++++++------- src/modules/sdlog2/sdlog2_messages.h | 14 +++++++------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 1820fc104..af580f1f7 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -998,7 +998,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_GS1B_s log_GS1B; struct log_TECS_s log_TECS; struct log_WIND_s log_WIND; - struct log_ENCODERS_s log_ENCODERS; + struct log_ENCD_s log_ENCD; } body; } log_msg = { LOG_PACKET_HEADER_INIT(0) @@ -1673,12 +1673,12 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- ENCODERS --- */ if (copy_if_updated(ORB_ID(encoders), subs.encoders_sub, &buf.encoders)) { - log_msg.msg_type = LOG_ENCODERS_MSG; - log_msg.body.log_ENCODERS.counts_0 = buf.encoders.counts[0]; - log_msg.body.log_ENCODERS.velocity_0 = buf.encoders.velocity[0]; - log_msg.body.log_ENCODERS.counts_1 = buf.encoders.counts[1]; - log_msg.body.log_ENCODERS.velocity_1 = buf.encoders.velocity[1]; - LOGBUFFER_WRITE_AND_COUNT(ENCODERS); + log_msg.msg_type = LOG_ENCD_MSG; + log_msg.body.log_ENCD.cnt0 = buf.encoders.counts[0]; + log_msg.body.log_ENCD.vel0 = buf.encoders.velocity[0]; + log_msg.body.log_ENCD.cnt1 = buf.encoders.counts[1]; + log_msg.body.log_ENCD.vel1 = buf.encoders.velocity[1]; + LOGBUFFER_WRITE_AND_COUNT(ENCD); } /* signal the other thread new data, but not yet unlock */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 7fd07809d..fa9bdacb8 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -408,12 +408,12 @@ struct log_VISN_s { }; /* --- ENCODERS - ENCODER DATA --- */ -#define LOG_ENCODERS_MSG 39 -struct log_ENCODERS_s { - int64_t counts_0; - float velocity_0; - int64_t counts_1; - float velocity_1; +#define LOG_ENCD_MSG 39 +struct log_ENCD_s { + int64_t cnt0; + float vel0; + int64_t cnt1; + float vel1; }; @@ -481,7 +481,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(TECS, "fffffffffffffB", "ASP,AF,FSP,F,FF,AsSP,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"), - LOG_FORMAT(ENCODERS, "qfqf", "counts_0, velocity_0, counts_1, velocity_1"), + LOG_FORMAT(ENCD, "qfqf", "cnt0,vel0,cnt1,vel1"), /* system-level messages, ID >= 0x80 */ /* FMT: don't write format of format message, it's useless */ -- cgit v1.2.3 From 82ebf3ca1c46dd228ed1a95fd334cae6af9dd252 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 21:23:02 +0100 Subject: Update NuttX, print stack trace on stack overflow handler --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 41fffa0df..5ee4b2b2c 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 41fffa0df192e4a26d2325c7ac5d9b5d7ba0211c +Subproject commit 5ee4b2b2c26bbc35d1669840f0676e8aa383b984 -- cgit v1.2.3 From b51c6693445be6ff230b3d34ad400553aadddd7e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 21:24:50 +0100 Subject: Commander: Improve calibration routines to produce more conscise and better sequenced instructions --- .../commander/accelerometer_calibration.cpp | 44 ++++++++++++++-------- src/modules/commander/airspeed_calibration.cpp | 25 ++++++++---- src/modules/commander/gyro_calibration.cpp | 5 ++- src/modules/commander/mag_calibration.cpp | 2 +- 4 files changed, 51 insertions(+), 25 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 7a4e7a766..0cb41489f 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -83,7 +83,7 @@ * | accel_T[1][i] | * [ accel_T[2][i] ] * - * b = [ accel_corr_ref[0][i] ] // One measurement per axis is enough + * b = [ accel_corr_ref[0][i] ] // One measurement per side is enough * | accel_corr_ref[2][i] | * [ accel_corr_ref[4][i] ] * @@ -162,6 +162,11 @@ int do_accel_calibration(int mavlink_fd) mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name); + mavlink_log_info(mavlink_fd, "You need to put the system on all six sides"); + sleep(3); + mavlink_log_info(mavlink_fd, "Follow the instructions on the screen"); + sleep(5); + struct accel_scale accel_scale = { 0.0f, 1.0f, @@ -258,7 +263,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float const int samples_num = 2500; float accel_ref[6][3]; bool data_collected[6] = { false, false, false, false, false, false }; - const char *orientation_strs[6] = { "x+", "x-", "y+", "y-", "z+", "z-" }; + const char *orientation_strs[6] = { "front", "back", "left", "right", "top", "bottom" }; int sensor_combined_sub = orb_subscribe(ORB_ID(sensor_combined)); @@ -287,29 +292,37 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float break; } - mavlink_log_info(mavlink_fd, "directions left: %s%s%s%s%s%s", - (!data_collected[0]) ? "x+ " : "", - (!data_collected[1]) ? "x- " : "", - (!data_collected[2]) ? "y+ " : "", - (!data_collected[3]) ? "y- " : "", - (!data_collected[4]) ? "z+ " : "", - (!data_collected[5]) ? "z- " : ""); + /* inform user which axes are still needed */ + mavlink_log_info(mavlink_fd, "pending: %s%s%s%s%s%s", + (!data_collected[0]) ? "front " : "", + (!data_collected[1]) ? "back " : "", + (!data_collected[2]) ? "left " : "", + (!data_collected[3]) ? "right " : "", + (!data_collected[4]) ? "up " : "", + (!data_collected[5]) ? "down " : ""); + + /* allow user enough time to read the message */ + sleep(3); int orient = detect_orientation(mavlink_fd, sensor_combined_sub); if (orient < 0) { - res = ERROR; - break; + mavlink_log_info(mavlink_fd, "invalid motion, hold still..."); + sleep(3); + continue; } + /* inform user about already handled side */ if (data_collected[orient]) { - mavlink_log_info(mavlink_fd, "%s done, rotate to a different axis", orientation_strs[orient]); + mavlink_log_info(mavlink_fd, "%s side done, rotate to a different side", orientation_strs[orient]); + sleep(4); continue; } - mavlink_log_info(mavlink_fd, "accel measurement started: %s axis", orientation_strs[orient]); + mavlink_log_info(mavlink_fd, "Hold still, starting to measure %s side", orientation_strs[orient]); + sleep(1); read_accelerometer_avg(sensor_combined_sub, &(accel_ref[orient][0]), samples_num); - mavlink_log_info(mavlink_fd, "result for %s axis: [ %.2f %.2f %.2f ]", orientation_strs[orient], + mavlink_log_info(mavlink_fd, "result for %s side: [ %.2f %.2f %.2f ]", orientation_strs[orient], (double)accel_ref[orient][0], (double)accel_ref[orient][1], (double)accel_ref[orient][2]); @@ -400,7 +413,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) /* is still now */ if (t_still == 0) { /* first time */ - mavlink_log_info(mavlink_fd, "detected rest position, waiting..."); + mavlink_log_info(mavlink_fd, "detected rest position, hold still..."); t_still = t; t_timeout = t + timeout; @@ -418,6 +431,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined) /* not still, reset still start time */ if (t_still != 0) { mavlink_log_info(mavlink_fd, "detected motion, hold still..."); + sleep(3); t_still = 0; } } diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 339b11bbe..cae1d7684 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -61,6 +61,15 @@ static const int ERROR = -1; static const char *sensor_name = "dpress"; +#define HUMAN_ASPD_CAL_FAILED_MSG "Calibration failed, see http://px4.io/help/aspd" + +static void feedback_calibration_failed(int mavlink_fd) +{ + sleep(5); + mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + mavlink_log_critical(mavlink_fd, HUMAN_ASPD_CAL_FAILED_MSG); +} + int do_airspeed_calibration(int mavlink_fd) { /* give directions */ @@ -99,7 +108,7 @@ int do_airspeed_calibration(int mavlink_fd) float analog_scaling = 0.0f; param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling)); if (fabsf(analog_scaling) < 0.1f) { - mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]"); + mavlink_log_critical(mavlink_fd, "No airspeed sensor, see http://px4.io/help/aspd"); close(diff_pres_sub); return ERROR; } @@ -138,7 +147,7 @@ int do_airspeed_calibration(int mavlink_fd) } else if (poll_ret == 0) { /* any poll failure for 1s is a reason to abort */ - mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + feedback_calibration_failed(mavlink_fd); close(diff_pres_sub); return ERROR; } @@ -175,7 +184,7 @@ int do_airspeed_calibration(int mavlink_fd) } } else { - mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name); + feedback_calibration_failed(mavlink_fd); close(diff_pres_sub); return ERROR; } @@ -207,7 +216,7 @@ int do_airspeed_calibration(int mavlink_fd) if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) { if (calibration_counter % 500 == 0) { - mavlink_log_info(mavlink_fd, "Create airflow! (%d, wanted: 50 Pa)", + mavlink_log_info(mavlink_fd, "Create air pressure! (got %d, wanted: 50 Pa)", (int)diff_pres.differential_pressure_raw_pa); } continue; @@ -215,9 +224,9 @@ int do_airspeed_calibration(int mavlink_fd) /* do not allow negative values */ if (diff_pres.differential_pressure_raw_pa < 0.0f) { - mavlink_log_critical(mavlink_fd, "Swap static and dynamic ports!"); mavlink_log_info(mavlink_fd, "ERROR: Negative pressure difference detected! (%d Pa)", (int)diff_pres.differential_pressure_raw_pa); + mavlink_log_critical(mavlink_fd, "Swap static and dynamic ports!"); close(diff_pres_sub); /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ @@ -235,7 +244,7 @@ int do_airspeed_calibration(int mavlink_fd) close(diff_pres_sub); - mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name); + feedback_calibration_failed(mavlink_fd); return ERROR; } else { mavlink_log_info(mavlink_fd, "Positive pressure: OK (%d Pa)", @@ -245,14 +254,14 @@ int do_airspeed_calibration(int mavlink_fd) } else if (poll_ret == 0) { /* any poll failure for 1s is a reason to abort */ - mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + feedback_calibration_failed(mavlink_fd); close(diff_pres_sub); return ERROR; } } if (calibration_counter == maxcount) { - mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + feedback_calibration_failed(mavlink_fd); close(diff_pres_sub); return ERROR; } diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index d89c67c2b..8ab14dd52 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -63,7 +63,10 @@ static const char *sensor_name = "gyro"; int do_gyro_calibration(int mavlink_fd) { mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name); - mavlink_log_info(mavlink_fd, "don't move system"); + mavlink_log_info(mavlink_fd, "HOLD STILL"); + + /* wait for the user to respond */ + sleep(2); struct gyro_scale gyro_scale = { 0.0f, diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 23900f386..7be8de9c6 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -155,7 +155,7 @@ int do_mag_calibration(int mavlink_fd) uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval; unsigned poll_errcount = 0; - mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis"); + mavlink_log_info(mavlink_fd, "Turn on all sides: front/back,left/right,up/down"); calibration_counter = 0; -- cgit v1.2.3 From 166580b8f7415de90f3e5c0171a75b9827158d12 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 21:41:55 +0100 Subject: Time out on serial instead of just hanging there --- Tools/px_uploader.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index b46db00b5..0bf2b82dd 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -178,9 +178,9 @@ class uploader(object): MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x80\x3f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x01\x00\x00\x48\xf0') MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x80\x3f\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x00\x00\x00\xd7\xac') - def __init__(self, portname, baudrate, interCharTimeout=0.001, timeout=0.5): + def __init__(self, portname, baudrate): # open the port, keep the default timeout short so we can poll quickly - self.port = serial.Serial(portname, baudrate) + self.port = serial.Serial(portname, baudrate, timeout=0.5) self.otp = b'' self.sn = b'' -- cgit v1.2.3 From 5862f4ffe6b463934cceb7bb034e77f100f97633 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 22:00:42 +0100 Subject: Fix error handling --- Tools/px_uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 0bf2b82dd..ea2f64639 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -195,7 +195,7 @@ class uploader(object): def __recv(self, count=1): c = self.port.read(count) if len(c) < 1: - raise RuntimeError("timeout waiting for data (%u bytes)", count) + raise RuntimeError("timeout waiting for data (%u bytes)" % count) # print("recv " + binascii.hexlify(c)) return c -- cgit v1.2.3 From 44a247363248caadecc4518048ab513d2dfd202e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 22:03:49 +0100 Subject: Fix up reboot logic --- Tools/px_uploader.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index ea2f64639..8a89fdf06 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -511,6 +511,8 @@ while True: up.send_reboot() # wait for the reboot, without we might run into Serial I/O Error 5 time.sleep(0.5) + # always close the port + up.close() continue try: -- cgit v1.2.3 From 72977ee9098758b5e00d9ac8df916bb221b2953f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 2 Nov 2014 22:13:59 +0100 Subject: Better error handling instructions --- Tools/px_uploader.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 8a89fdf06..d4e461226 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -459,6 +459,7 @@ if os.path.exists("/usr/sbin/ModemManager"): # Load the firmware file fw = firmware(args.firmware) print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'))) +print("If the board does not respond within 1-2 seconds, unplug and re-plug the USB connector.") # Spin waiting for a device to show up while True: @@ -508,6 +509,7 @@ while True: except Exception: # most probably a timeout talking to the port, no bootloader, try to reboot the board print("attempting reboot on %s..." % port) + print("if the board does not respond, unplug and re-plug the USB connector.") up.send_reboot() # wait for the reboot, without we might run into Serial I/O Error 5 time.sleep(0.5) -- cgit v1.2.3 From 5e2330abbae35bfc45e5ac67d3590b53de20f526 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 3 Nov 2014 08:39:16 +0100 Subject: Add USB load test from Mark Whitehorn --- Tools/usb_serialload.py | 55 +++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 55 insertions(+) create mode 100644 Tools/usb_serialload.py diff --git a/Tools/usb_serialload.py b/Tools/usb_serialload.py new file mode 100644 index 000000000..5c864532f --- /dev/null +++ b/Tools/usb_serialload.py @@ -0,0 +1,55 @@ +import serial, time + + +port = serial.Serial('/dev/ttyACM0', baudrate=57600, timeout=2) + +data = '01234567890123456789012345678901234567890123456789' +#data = 'hellohello' +outLine = 'echo %s\n' % data + +port.write('\n\n\n') +port.write('free\n') +line = port.readline(80) +while line != '': + print(line) + line = port.readline(80) + + +i = 0 +bytesOut = 0 +bytesIn = 0 + +startTime = time.time() +lastPrint = startTime +while True: + bytesOut += port.write(outLine) + line = port.readline(80) + bytesIn += len(line) + # check command line echo + if (data not in line): + print('command error %d: %s' % (i,line)) + #break + # read echo output + line = port.readline(80) + if (data not in line): + print('echo output error %d: %s' % (i,line)) + #break + bytesIn += len(line) + #print('%d: %s' % (i,line)) + #print('%d: bytesOut: %d, bytesIn: %d' % (i, bytesOut, bytesIn)) + + elapsedT = time.time() - lastPrint + if (time.time() - lastPrint >= 5): + outRate = bytesOut / elapsedT + inRate = bytesIn / elapsedT + usbRate = (bytesOut + bytesIn) / elapsedT + lastPrint = time.time() + print('elapsed time: %f' % (time.time() - startTime)) + print('data rates (bytes/sec): out: %f, in: %f, total: %f' % (outRate, inRate, usbRate)) + + bytesOut = 0 + bytesIn = 0 + + i += 1 + #if (i > 2): break + -- cgit v1.2.3 From 9ac13745f8356db60322fa92ecdff1125c76f172 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 3 Nov 2014 09:48:06 +0100 Subject: Adjust MAVLink RX prio to ensure received data can still be processed --- 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 9247f999a..bc092c7e9 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1396,7 +1396,7 @@ MavlinkReceiver::receive_start(Mavlink *parent) struct sched_param param; (void)pthread_attr_getschedparam(&receiveloop_attr, ¶m); - param.sched_priority = SCHED_PRIORITY_MAX - 40; + param.sched_priority = SCHED_PRIORITY_MAX - 80; (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); pthread_attr_setstacksize(&receiveloop_attr, 2900); -- cgit v1.2.3 From 8652ee0b6474fa4fa92b0d6ab5eaec1436a03b8b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 3 Nov 2014 09:48:24 +0100 Subject: Drop NSH priority to keep system responsive --- src/systemcmds/nshterm/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk index 41706e137..a12bc369e 100644 --- a/src/systemcmds/nshterm/module.mk +++ b/src/systemcmds/nshterm/module.mk @@ -41,3 +41,5 @@ SRCS = nshterm.c MODULE_STACKSIZE = 1600 MAXOPTIMIZATION = -Os + +MODULE_PRIORITY = "SCHED_PRIORITY_DEFAULT-30" -- cgit v1.2.3 From 06df0f23a32c87486815a9794c1425fe4534ac13 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 3 Nov 2014 12:56:35 +0100 Subject: L3GD20: Output gyro temperature in report --- src/drivers/l3gd20/l3gd20.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index cfae8761c..ff2871354 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -176,6 +176,7 @@ static const int ERROR = -1; #define L3G4200D_DEFAULT_RATE 800 #define L3GD20_DEFAULT_RANGE_DPS 2000 #define L3GD20_DEFAULT_FILTER_FREQ 30 +#define L3GD20_TEMP_OFFSET_CELCIUS 40 #ifndef SENSOR_BOARD_ROTATION_DEFAULT #define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG @@ -856,7 +857,7 @@ L3GD20::measure() #pragma pack(push, 1) struct { uint8_t cmd; - uint8_t temp; + int8_t temp; uint8_t status; int16_t x; int16_t y; @@ -930,6 +931,8 @@ L3GD20::measure() report.z_raw = raw_report.z; + report.temperature_raw = raw_report.temp; + report.x = ((report.x_raw * _gyro_range_scale) - _gyro_scale.x_offset) * _gyro_scale.x_scale; report.y = ((report.y_raw * _gyro_range_scale) - _gyro_scale.y_offset) * _gyro_scale.y_scale; report.z = ((report.z_raw * _gyro_range_scale) - _gyro_scale.z_offset) * _gyro_scale.z_scale; @@ -938,6 +941,8 @@ L3GD20::measure() report.y = _gyro_filter_y.apply(report.y); report.z = _gyro_filter_z.apply(report.z); + report.temperature = L3GD20_TEMP_OFFSET_CELCIUS - raw_report.temp; + // apply user specified rotation rotate_3f(_rotation, report.x, report.y, report.z); @@ -1091,9 +1096,11 @@ test() warnx("gyro x: \t% 9.5f\trad/s", (double)g_report.x); warnx("gyro y: \t% 9.5f\trad/s", (double)g_report.y); warnx("gyro z: \t% 9.5f\trad/s", (double)g_report.z); + warnx("temp: \t%d\tC", (int)g_report.temperature); warnx("gyro x: \t%d\traw", (int)g_report.x_raw); warnx("gyro y: \t%d\traw", (int)g_report.y_raw); warnx("gyro z: \t%d\traw", (int)g_report.z_raw); + warnx("temp: \t%d\traw", (int)g_report.temperature_raw); warnx("gyro range: %8.4f rad/s (%d deg/s)", (double)g_report.range_rad_s, (int)((g_report.range_rad_s / M_PI_F) * 180.0f + 0.5f)); -- cgit v1.2.3 From c600a7fbd27c298e855d1f3e6f00f590141f995e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 3 Nov 2014 15:37:24 +0100 Subject: L3GD20: Fix typo --- src/drivers/l3gd20/l3gd20.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index ff2871354..82fa5cc6e 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -176,7 +176,7 @@ static const int ERROR = -1; #define L3G4200D_DEFAULT_RATE 800 #define L3GD20_DEFAULT_RANGE_DPS 2000 #define L3GD20_DEFAULT_FILTER_FREQ 30 -#define L3GD20_TEMP_OFFSET_CELCIUS 40 +#define L3GD20_TEMP_OFFSET_CELSIUS 40 #ifndef SENSOR_BOARD_ROTATION_DEFAULT #define SENSOR_BOARD_ROTATION_DEFAULT SENSOR_BOARD_ROTATION_270_DEG @@ -941,7 +941,7 @@ L3GD20::measure() report.y = _gyro_filter_y.apply(report.y); report.z = _gyro_filter_z.apply(report.z); - report.temperature = L3GD20_TEMP_OFFSET_CELCIUS - raw_report.temp; + report.temperature = L3GD20_TEMP_OFFSET_CELSIUS - raw_report.temp; // apply user specified rotation rotate_3f(_rotation, report.x, report.y, report.z); -- cgit v1.2.3 From 58f36714f808c9d06527da1952d348201c4f7e72 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Thu, 14 Aug 2014 15:43:27 +0200 Subject: UAVCAN: allow to arm single ESCs --- src/modules/uavcan/actuators/esc.cpp | 26 +++++++++++++++++++++----- src/modules/uavcan/actuators/esc.hpp | 9 ++++++++- src/modules/uavcan/uavcan_main.cpp | 2 +- 3 files changed, 30 insertions(+), 7 deletions(-) diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index 1990651ef..fbd4f0bcd 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -40,6 +40,9 @@ #include "esc.hpp" #include + +#define MOTOR_BIT(x) (1<<(x)) + UavcanEscController::UavcanEscController(uavcan::INode &node) : _node(node), _uavcan_pub_raw_cmd(node), @@ -95,9 +98,8 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) static const int cmd_max = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max(); - if (_armed) { - for (unsigned i = 0; i < num_outputs; i++) { - + for (unsigned i = 0; i < num_outputs; i++) { + if (_armed_mask & MOTOR_BIT(i)) { float scaled = (outputs[i] + 1.0F) * 0.5F * cmd_max; if (scaled < 1.0F) { scaled = 1.0F; // Since we're armed, we don't want to stop it completely @@ -112,6 +114,9 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) _esc_status.esc[i].esc_setpoint_raw = abs(static_cast(scaled)); } + else { + msg.cmd.push_back(static_cast(0)); + } } /* @@ -121,9 +126,20 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) (void)_uavcan_pub_raw_cmd.broadcast(msg); } -void UavcanEscController::arm_esc(bool arm) +void UavcanEscController::arm_all_escs(bool arm) +{ + if (arm) + _armed_mask = -1; + else + _armed_mask = 0; +} + +void UavcanEscController::arm_single_esc(int num, bool arm) { - _armed = arm; + if (arm) + _armed_mask = MOTOR_BIT(num); + else + _armed_mask = 0; } void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure &msg) diff --git a/src/modules/uavcan/actuators/esc.hpp b/src/modules/uavcan/actuators/esc.hpp index f4a3877e6..ff3ecfb21 100644 --- a/src/modules/uavcan/actuators/esc.hpp +++ b/src/modules/uavcan/actuators/esc.hpp @@ -61,7 +61,8 @@ public: void update_outputs(float *outputs, unsigned num_outputs); - void arm_esc(bool arm); + void arm_all_escs(bool arm); + void arm_single_esc(int num, bool arm); private: /** @@ -98,6 +99,12 @@ private: uavcan::Subscriber _uavcan_sub_status; uavcan::TimerEventForwarder _orb_timer; + /* + * ESC states + */ + uint32_t _armed_mask = 0; + uavcan::equipment::esc::Status _states[MAX_ESCS]; + /* * Perf counters */ diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index a8485ee44..59f0f4300 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -429,7 +429,7 @@ int UavcanNode::arm_actuators(bool arm) { _is_armed = arm; - _esc_controller.arm_esc(arm); + _esc_controller.arm_all_escs(arm); return OK; } -- cgit v1.2.3 From a18460183cdfa590af29c2299acb30206b418cb1 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Mon, 3 Nov 2014 19:37:44 +0100 Subject: motor_test: cleanup --- src/modules/uORB/topics/test_motor.h | 2 +- src/systemcmds/motor_test/motor_test.c | 23 ++++++++++++----------- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/src/modules/uORB/topics/test_motor.h b/src/modules/uORB/topics/test_motor.h index 491096934..c880fe099 100644 --- a/src/modules/uORB/topics/test_motor.h +++ b/src/modules/uORB/topics/test_motor.h @@ -57,7 +57,7 @@ struct test_motor_s { uint64_t timestamp; /**< output timestamp in us since system boot */ unsigned motor_number; /**< number of motor to spin */ - float value; /**< output data, in natural output units */ + float value; /**< output power, range [0..1] }; /** diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c index 079f99674..a73f46626 100644 --- a/src/systemcmds/motor_test/motor_test.c +++ b/src/systemcmds/motor_test/motor_test.c @@ -54,7 +54,8 @@ #include "systemlib/err.h" -__EXPORT int motor_test_main(int argc, char *argv[]); +__EXPORT int motor_test_main(int argc, char *argv[]); + static void motor_test(unsigned channel, float value); static void usage(const char *reason); @@ -67,13 +68,13 @@ void motor_test(unsigned channel, float value) _test_motor.timestamp = hrt_absolute_time(); _test_motor.value = value; - if (_test_motor_pub > 0) { - /* publish armed state */ - orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor); - } else { - /* advertise and publish */ - _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor); - } + if (_test_motor_pub > 0) { + /* publish test state */ + orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor); + } else { + /* advertise and publish */ + _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor); + } } static void usage(const char *reason) @@ -102,18 +103,18 @@ int motor_test_main(int argc, char *argv[]) switch (ch) { case 'm': - /* Read in channels supplied as one int and convert to mask: 1234 -> 0xF */ + /* Read in motor number */ channel = strtoul(optarg, NULL, 0); break; case 'p': - /* Read in custom low value */ + /* Read in power value */ lval = strtoul(optarg, NULL, 0); if (lval > 100) usage("value invalid"); - value = (float)lval/100.f; + value = ((float)lval)/100.f; break; default: usage(NULL); -- cgit v1.2.3 From 0800fa4715994921b6a0d15cd2c44b9e51417117 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Mon, 3 Nov 2014 18:47:07 +0100 Subject: UAVCAN: implemented motor testing --- src/modules/uavcan/actuators/esc.hpp | 1 - src/modules/uavcan/uavcan_main.cpp | 28 ++++++++++++++++++++++++---- src/modules/uavcan/uavcan_main.hpp | 5 +++++ 3 files changed, 29 insertions(+), 5 deletions(-) diff --git a/src/modules/uavcan/actuators/esc.hpp b/src/modules/uavcan/actuators/esc.hpp index ff3ecfb21..12c035542 100644 --- a/src/modules/uavcan/actuators/esc.hpp +++ b/src/modules/uavcan/actuators/esc.hpp @@ -103,7 +103,6 @@ private: * ESC states */ uint32_t _armed_mask = 0; - uavcan::equipment::esc::Status _states[MAX_ESCS]; /* * Perf counters diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 59f0f4300..653d4f98c 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -279,6 +279,7 @@ int UavcanNode::run() _output_count = 2; _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); + _test_motor_sub = orb_subscribe(ORB_ID(test_motor)); actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); @@ -344,7 +345,14 @@ int UavcanNode::run() } // can we mix? - if (controls_updated && (_mixers != nullptr)) { + if (_test_in_progress) { + float outputs[NUM_ACTUATOR_OUTPUTS] = {}; + outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f; + + // Output to the bus + _esc_controller.update_outputs(outputs, NUM_ACTUATOR_OUTPUTS); + } + else if (controls_updated && (_mixers != nullptr)) { // XXX one output group has 8 outputs max, // but this driver could well serve multiple groups. @@ -384,15 +392,27 @@ int UavcanNode::run() } } - // Check arming state + // Check motor test state bool updated = false; + orb_check(_test_motor_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(test_motor), _test_motor_sub, &_test_motor); + + // Update the test status and check that we're not locked down + _test_in_progress = (_test_motor.value > 0); + _esc_controller.arm_single_esc(_test_motor.motor_number, _test_in_progress); + } + + // Check arming state orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); - // Update the armed status and check that we're not locked down - bool set_armed = _armed.armed && !_armed.lockdown; + // Update the armed status and check that we're not locked down and motor + // test is not running + bool set_armed = _armed.armed && !_armed.lockdown && !_test_in_progress; arm_actuators(set_armed); } diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index be7db9741..274321f0d 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -41,6 +41,7 @@ #include #include #include +#include #include "actuators/esc.hpp" #include "sensors/sensor_bridge.hpp" @@ -103,6 +104,10 @@ private: actuator_armed_s _armed; ///< the arming request of the system bool _is_armed = false; ///< the arming status of the actuators on the bus + int _test_motor_sub = -1; ///< uORB subscription of the test_motor status + test_motor_s _test_motor; + bool _test_in_progress = false; + unsigned _output_count = 0; ///< number of actuators currently available static UavcanNode *_instance; ///< singleton pointer -- cgit v1.2.3 From f5dbfe63b3d7fbfcac524ba03028de962a8716e2 Mon Sep 17 00:00:00 2001 From: tumbili Date: Tue, 4 Nov 2014 20:52:29 +0100 Subject: added new sensor board rotation option (roll 270, yaw 270) --- src/lib/conversion/rotation.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h index 5187b448f..739c3a960 100644 --- a/src/lib/conversion/rotation.h +++ b/src/lib/conversion/rotation.h @@ -74,6 +74,7 @@ enum Rotation { ROTATION_ROLL_270_YAW_135 = 23, ROTATION_PITCH_90 = 24, ROTATION_PITCH_270 = 25, + ROTATION_ROLL_270_YAW_270 = 26, ROTATION_MAX }; @@ -109,7 +110,8 @@ const rot_lookup_t rot_lookup[] = { {270, 0, 90 }, {270, 0, 135 }, { 0, 90, 0 }, - { 0, 270, 0 } + { 0, 270, 0 }, + {270, 0, 270 } }; /** -- cgit v1.2.3 From cbd20f48d670749fcbfe49c0f5135572bdf7ee44 Mon Sep 17 00:00:00 2001 From: tumbili Date: Tue, 4 Nov 2014 20:57:09 +0100 Subject: fixed style --- src/lib/conversion/rotation.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h index 739c3a960..917c7f830 100644 --- a/src/lib/conversion/rotation.h +++ b/src/lib/conversion/rotation.h @@ -74,7 +74,7 @@ enum Rotation { ROTATION_ROLL_270_YAW_135 = 23, ROTATION_PITCH_90 = 24, ROTATION_PITCH_270 = 25, - ROTATION_ROLL_270_YAW_270 = 26, + ROTATION_ROLL_270_YAW_270 = 26, ROTATION_MAX }; -- cgit v1.2.3 From 182c1c1d52ef370a42b99c825e3f45a03ecbcdc9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Nov 2014 17:17:34 +0100 Subject: Fix RC mapping indices - 0 index induces issues right now --- src/drivers/px4io/px4io.cpp | 15 ++++++++++----- 1 file changed, 10 insertions(+), 5 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index fd9eb4170..c6543982e 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1247,28 +1247,33 @@ PX4IO::io_set_rc_config() */ param_get(param_find("RC_MAP_ROLL"), &ichan); + /* subtract one from 1-based index - this might be + * a negative number now + */ + ichan -= 1; + if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan - 1] = 0; + input_map[ichan] = 0; param_get(param_find("RC_MAP_PITCH"), &ichan); if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan - 1] = 1; + input_map[ichan] = 1; param_get(param_find("RC_MAP_YAW"), &ichan); if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan - 1] = 2; + input_map[ichan] = 2; param_get(param_find("RC_MAP_THROTTLE"), &ichan); if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan - 1] = 3; + input_map[ichan] = 3; param_get(param_find("RC_MAP_FLAPS"), &ichan); if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan - 1] = 4; + input_map[ichan] = 4; param_get(param_find("RC_MAP_MODE_SW"), &ichan); -- cgit v1.2.3 From 23a33e31cd91d074f2d16d04b0cd7f2c867d9d4b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 5 Nov 2014 19:26:10 +0100 Subject: Add missing mode switch channel --- src/drivers/px4io/px4io.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index c6543982e..6d68d9f60 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1279,7 +1279,7 @@ PX4IO::io_set_rc_config() if ((ichan >= 0) && (ichan < (int)_max_rc_input)) { /* use out of normal bounds index to indicate special channel */ - input_map[ichan - 1] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH; + input_map[ichan] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH; } /* -- cgit v1.2.3 From d907b030ee618b581e31964a34a61648e88793a3 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Wed, 5 Nov 2014 13:15:52 -0800 Subject: Initialize RSSI so it doesn't remain uninitialized MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Spektrum doesn’t support rssi so it is not set by st24_decode. --- src/modules/px4iofirmware/controls.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index ad60ee03e..3fd73fc60 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -41,6 +41,7 @@ #include #include +#include #include #include #include @@ -91,6 +92,7 @@ bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated) for (unsigned i = 0; i < n_bytes; i++) { /* set updated flag if one complete packet was parsed */ + st24_rssi = RC_INPUT_RSSI_MAX; *st24_updated |= (OK == st24_decode(bytes[i], &st24_rssi, &rx_count, &st24_channel_count, r_raw_rc_values, PX4IO_RC_INPUT_CHANNELS)); } -- cgit v1.2.3 From f414eef042be7ebf641638009b3676523bf4bed6 Mon Sep 17 00:00:00 2001 From: philipoe Date: Tue, 4 Nov 2014 11:10:14 +0100 Subject: TECS: Modify absolute-value limiting of throttle demand --- src/lib/external_lgpl/tecs/tecs.cpp | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 0ed210cf4..cfcc48b62 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -321,31 +321,29 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM ff_throttle = nomThr - STEdot_dem / _STEdot_min * nomThr; } - // Calculate PD + FF throttle + // Calculate PD + FF throttle and constrain to avoid blow-up of the integrator later _throttle_dem = (_STE_error + STEdot_error * _thrDamp) * K_STE2Thr + ff_throttle; + _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf); // Rate limit PD + FF throttle // Calculate the throttle increment from the specified slew time if (fabsf(_throttle_slewrate) > 0.01f) { float thrRateIncr = _DT * (_THRmaxf - _THRminf) * _throttle_slewrate; - _throttle_dem = constrain(_throttle_dem, - _last_throttle_dem - thrRateIncr, - _last_throttle_dem + thrRateIncr); + _last_throttle_dem - thrRateIncr, + _last_throttle_dem + thrRateIncr); } // Ensure _last_throttle_dem is always initialized properly - // Also: The throttle_slewrate limit is only applied to throttle_dem, but does not limit the integrator!! _last_throttle_dem = _throttle_dem; - // Calculate integrator state upper and lower limits - // Set to a value thqat will allow 0.1 (10%) throttle saturation to allow for noise on the demand + // Set to a value that will allow 0.1 (10%) throttle saturation to allow for noise on the demand float integ_max = (_THRmaxf - _throttle_dem + 0.1f); float integ_min = (_THRminf - _throttle_dem - 0.1f); // Calculate integrator state, constraining state - // Set integrator to a max throttle value dduring climbout + // Set integrator to a max throttle value during climbout _integ6_state = _integ6_state + (_STE_error * _integGain) * _DT * K_STE2Thr; if (_climbOutDem) { -- cgit v1.2.3 From 3f3353f2c4ad9f7b8263379c8b31bd9a437b0174 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 5 Nov 2014 21:19:04 +1100 Subject: mixer: fixed stream handle leakage --- src/modules/systemlib/mixer/mixer_load.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/systemlib/mixer/mixer_load.c b/src/modules/systemlib/mixer/mixer_load.c index bf3428a50..0d629d610 100644 --- a/src/modules/systemlib/mixer/mixer_load.c +++ b/src/modules/systemlib/mixer/mixer_load.c @@ -91,6 +91,7 @@ int load_mixer_file(const char *fname, char *buf, unsigned maxlen) /* if the line is too long to fit in the buffer, bail */ if ((strlen(line) + strlen(buf) + 1) >= maxlen) { warnx("line too long"); + fclose(fp); return -1; } @@ -98,6 +99,7 @@ int load_mixer_file(const char *fname, char *buf, unsigned maxlen) strcat(buf, line); } + fclose(fp); return 0; } -- cgit v1.2.3 From 43418a674903d242271028c4d4eb473f95a24be6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 7 Nov 2014 13:31:33 +0100 Subject: application layer only, no drivers affected: Fix overflow in RC input topic - this topic is deprecated and will be removed, has been superseded by input_rc and manual_control --- src/modules/uORB/topics/rc_channels.h | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h index b14ae1edd..16916cc4d 100644 --- a/src/modules/uORB/topics/rc_channels.h +++ b/src/modules/uORB/topics/rc_channels.h @@ -34,6 +34,8 @@ /** * @file rc_channels.h * Definition of the rc_channels uORB topic. + * + * @deprecated DO NOT USE FOR NEW CODE */ #ifndef RC_CHANNELS_H_ @@ -63,10 +65,13 @@ enum RC_CHANNELS_FUNCTION { AUX_2, AUX_3, AUX_4, - AUX_5, - RC_CHANNELS_FUNCTION_MAX /**< Indicates the number of functions. There can be more functions than RC channels. */ + AUX_5 }; +// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS + +#define RC_CHANNELS_FUNCTION_MAX 18 + /** * @addtogroup topics * @{ -- cgit v1.2.3 From 02d31522cde1de13ab397f4fbd77c0cf9b7f712d Mon Sep 17 00:00:00 2001 From: Daniel Shiels Date: Wed, 29 Oct 2014 22:00:30 +1100 Subject: First attempt at sbus1 output. --- src/modules/px4iofirmware/sbus.c | 37 ++++++++++++++++++++++++++++++++++--- 1 file changed, 34 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 6ead38d61..23dae7898 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -80,8 +80,10 @@ static int sbus_fd = -1; static hrt_abstime last_rx_time; static hrt_abstime last_frame_time; +static hrt_abstime last_txframe_time=0; static uint8_t frame[SBUS_FRAME_SIZE]; +static uint8_t oframe[SBUS_FRAME_SIZE]; static unsigned partial_frame_count; @@ -122,10 +124,39 @@ sbus_init(const char *device) void sbus1_output(uint16_t *values, uint16_t num_values) { - char a = 'A'; - write(sbus_fd, &a, 1); -} + //int. first byte of data is offset 1 in sbus + uint8_t byteindex=1; + uint8_t offset=0; + uint16_t value; + hrt_abstime now; + //oframe[0]=0xf0; + oframe[0]=0x0f; + now = hrt_absolute_time(); + if ((now - last_txframe_time) > 14000) { + last_txframe_time = now; + + for (uint16_t i=1;i=8) { + ++byteindex; + offset-=8; + } + oframe[byteindex] |= (value<<(offset))&0xff; + oframe[byteindex+1]|=(value>>(8-offset))&0xff; + oframe[byteindex+2]|=(value>>(16-offset))&0xff; + offset+=11; + } + write(sbus_fd, oframe, SBUS_FRAME_SIZE); + } +} void sbus2_output(uint16_t *values, uint16_t num_values) { -- cgit v1.2.3 From 60ecd8868db3539e552bad5f51473d1baf5d6ecd Mon Sep 17 00:00:00 2001 From: Daniel Shiels Date: Sat, 8 Nov 2014 22:36:45 +1100 Subject: sbus1 output. Cleaned up. Safer bounds checking. --- src/modules/px4iofirmware/sbus.c | 45 +++++++++++++++++++++++----------------- 1 file changed, 26 insertions(+), 19 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 23dae7898..2f234234e 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -57,6 +57,7 @@ #define SBUS_FLAGS_BYTE 23 #define SBUS_FAILSAFE_BIT 3 #define SBUS_FRAMELOST_BIT 2 +#define SBUS1_FRAME_DELAY 14000 /* Measured values with Futaba FX-30/R6108SB: @@ -80,7 +81,7 @@ static int sbus_fd = -1; static hrt_abstime last_rx_time; static hrt_abstime last_frame_time; -static hrt_abstime last_txframe_time=0; +static hrt_abstime last_txframe_time = 0; static uint8_t frame[SBUS_FRAME_SIZE]; static uint8_t oframe[SBUS_FRAME_SIZE]; @@ -125,35 +126,41 @@ void sbus1_output(uint16_t *values, uint16_t num_values) { //int. first byte of data is offset 1 in sbus - uint8_t byteindex=1; - uint8_t offset=0; + uint8_t byteindex = 1; + uint8_t offset = 0; uint16_t value; hrt_abstime now; - //oframe[0]=0xf0; - oframe[0]=0x0f; + oframe[0] = 0x0f; - now = hrt_absolute_time(); - if ((now - last_txframe_time) > 14000) { + now = hrt_absolute_time(); + + if ((now - last_txframe_time) > SBUS1_FRAME_DELAY) { last_txframe_time = now; - for (uint16_t i=1;i=8) { + if (value > 0x07ff ) { + value = 0x07ff; + } + + while (offset >= 8) { ++byteindex; - offset-=8; + offset -= 8; } - oframe[byteindex] |= (value<<(offset))&0xff; - oframe[byteindex+1]|=(value>>(8-offset))&0xff; - oframe[byteindex+2]|=(value>>(16-offset))&0xff; - offset+=11; - } + + oframe[byteindex] |= (value << (offset)) & 0xff; + oframe[byteindex + 1] |= (value >> (8 - offset)) & 0xff; + oframe[byteindex + 2] |= (value >> (16 - offset)) & 0xff; + offset += 11; + } + write(sbus_fd, oframe, SBUS_FRAME_SIZE); } } -- cgit v1.2.3 From 8599994ebb3e4ce63b5fe77cb1f2935d27604745 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 8 Nov 2014 20:38:57 +0100 Subject: Add generic uploader tool --- Tools/upload.sh | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) create mode 100755 Tools/upload.sh diff --git a/Tools/upload.sh b/Tools/upload.sh new file mode 100755 index 000000000..17d87fe61 --- /dev/null +++ b/Tools/upload.sh @@ -0,0 +1,28 @@ +#!/bin/bash + +EXEDIR=`pwd` +BASEDIR=$(dirname $0) + +SYSTYPE=`uname -s` + +# +# Serial port defaults. +# +# XXX The uploader should be smarter than this. +# +if [ $SYSTYPE=Darwin ]; +then +SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*" +fi + +if [ $SYSTYPE=Linux ]; +then +SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*" +fi + +if [ $SYSTYPE="" ]; +then +SERIAL_PORTS="COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0" +fi + +python $BASEDIR/px_uploader.py --port $SERIAL_PORTS $1 \ No newline at end of file -- cgit v1.2.3 From e87a179fc1b9b10bfd22e741229e9cbd75b6ef73 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 9 Nov 2014 15:16:05 +0100 Subject: MAVLink update --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 90383fac8..ad5e5a645 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 90383fac84d031aef17989a1497c2473dfa64340 +Subproject commit ad5e5a645dec152419264ad32221f7c113ea5c30 -- cgit v1.2.3 From 62db84fa758ecc30081e30a18464fe3060d2c2d8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 9 Nov 2014 18:20:53 +0100 Subject: MAVLink update compile fixes --- src/modules/mavlink/mavlink.c | 6 +----- src/modules/mavlink/mavlink_main.cpp | 12 +++++++----- src/modules/mavlink/mavlink_main.h | 4 ++++ src/modules/mavlink/mavlink_messages.cpp | 12 +++++++----- 4 files changed, 19 insertions(+), 15 deletions(-) diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index bec706bad..9afe74af1 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -78,11 +78,7 @@ PARAM_DEFINE_INT32(MAV_FWDEXTSP, 1); mavlink_system_t mavlink_system = { 100, - 50, - MAV_TYPE_FIXED_WING, - 0, - 0, - 0 + 50 }; // System ID, 1-255, Component/Subsystem ID, 1-255 /* diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 6b4edff78..c251dd3b2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -167,8 +167,10 @@ Mavlink::Mavlink() : _param_initialized(false), _param_system_id(0), _param_component_id(0), - _param_system_type(0), + _param_system_type(MAV_TYPE_FIXED_WING), _param_use_hil_gps(0), + _param_forward_externalsp(0), + _system_type(0), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), @@ -524,7 +526,7 @@ void Mavlink::mavlink_update_system(void) param_get(_param_system_type, &system_type); if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) { - mavlink_system.type = system_type; + _system_type = system_type; } int32_t use_hil_gps; @@ -755,7 +757,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) pthread_mutex_lock(&_send_mutex); - int buf_free = get_free_tx_buf(); + unsigned buf_free = get_free_tx_buf(); uint8_t payload_len = mavlink_message_lengths[msgid]; unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES; @@ -820,14 +822,14 @@ Mavlink::resend_message(mavlink_message_t *msg) pthread_mutex_lock(&_send_mutex); - int buf_free = get_free_tx_buf(); + unsigned buf_free = get_free_tx_buf(); _last_write_try_time = hrt_absolute_time(); unsigned packet_len = msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; /* check if there is space in the buffer, let it overflow else */ - if (buf_free < TX_BUFFER_GAP) { + if ((buf_free < TX_BUFFER_GAP) || (buf_free < packet_len)) { /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 1f96e586b..ad5e5001b 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -265,6 +265,8 @@ public: struct mavlink_logbuffer *get_logbuffer() { return &_logbuffer; } + unsigned get_system_type() { return _system_type; } + protected: Mavlink *next; @@ -354,6 +356,8 @@ private: param_t _param_use_hil_gps; param_t _param_forward_externalsp; + unsigned _system_type; + perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _txerr_perf; /**< TX error counter */ diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index cccb698bf..b4911427f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -302,7 +302,7 @@ protected: msg.base_mode = 0; msg.custom_mode = 0; get_mavlink_mode_state(&status, &pos_sp_triplet, &msg.system_status, &msg.base_mode, &msg.custom_mode); - msg.type = mavlink_system.type; + msg.type = _mavlink->get_system_type(); msg.autopilot = MAV_AUTOPILOT_PX4; msg.mavlink_version = 3; @@ -1353,15 +1353,17 @@ protected: const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; + unsigned system_type = _mavlink->get_system_type(); + /* scale outputs depending on system type */ - if (mavlink_system.type == MAV_TYPE_QUADROTOR || - mavlink_system.type == MAV_TYPE_HEXAROTOR || - mavlink_system.type == MAV_TYPE_OCTOROTOR) { + if (system_type == MAV_TYPE_QUADROTOR || + system_type == MAV_TYPE_HEXAROTOR || + system_type == MAV_TYPE_OCTOROTOR) { /* multirotors: set number of rotor outputs depending on type */ unsigned n; - switch (mavlink_system.type) { + switch (system_type) { case MAV_TYPE_QUADROTOR: n = 4; break; -- cgit v1.2.3 From 34e9d9efce10ce487b4c5af0cf93a442ab3b8594 Mon Sep 17 00:00:00 2001 From: Daniel Shiels Date: Mon, 10 Nov 2014 15:54:28 +1100 Subject: Code style cleanup. --- src/modules/px4iofirmware/sbus.c | 13 +++++++------ 1 file changed, 7 insertions(+), 6 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 2f234234e..90c0e0503 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -125,8 +125,7 @@ sbus_init(const char *device) void sbus1_output(uint16_t *values, uint16_t num_values) { - //int. first byte of data is offset 1 in sbus - uint8_t byteindex = 1; + uint8_t byteindex = 1; /*Data starts one byte into the sbus frame. */ uint8_t offset = 0; uint16_t value; hrt_abstime now; @@ -141,11 +140,13 @@ sbus1_output(uint16_t *values, uint16_t num_values) oframe[i] = 0; } - // 16 is sbus number of servos/channels minus 2 single bit channels. - // currently ignoring single bit channels. - for (uint16_t i = 0; (i < num_values) && (i < 16); ++i) { + /* 16 is sbus number of servos/channels minus 2 single bit channels. + * currently ignoring single bit channels. */ + + for (unsigned i = 0; (i < num_values) && (i < 16); ++i) { value = (uint16_t)(((values[i] - SBUS_SCALE_OFFSET) / SBUS_SCALE_FACTOR) + .5f); - //protect from out of bounds values and limit to 11 bits; + + /*protect from out of bounds values and limit to 11 bits*/ if (value > 0x07ff ) { value = 0x07ff; } -- cgit v1.2.3 From 3eeec2cce05c8f32a5c2d70b956786d41114df3c Mon Sep 17 00:00:00 2001 From: Daniel Shiels Date: Mon, 10 Nov 2014 16:34:28 +1100 Subject: Cleaned up sbus output frame initialisation. --- src/modules/px4iofirmware/sbus.c | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 90c0e0503..d76ec55f0 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -84,7 +84,6 @@ static hrt_abstime last_frame_time; static hrt_abstime last_txframe_time = 0; static uint8_t frame[SBUS_FRAME_SIZE]; -static uint8_t oframe[SBUS_FRAME_SIZE]; static unsigned partial_frame_count; @@ -128,17 +127,13 @@ sbus1_output(uint16_t *values, uint16_t num_values) uint8_t byteindex = 1; /*Data starts one byte into the sbus frame. */ uint8_t offset = 0; uint16_t value; - hrt_abstime now; - oframe[0] = 0x0f; + hrt_abstime now; now = hrt_absolute_time(); if ((now - last_txframe_time) > SBUS1_FRAME_DELAY) { last_txframe_time = now; - - for (uint16_t i = 1; i < SBUS_FRAME_SIZE; ++i) { - oframe[i] = 0; - } + uint8_t oframe[SBUS_FRAME_SIZE] = { 0x0f }; /* 16 is sbus number of servos/channels minus 2 single bit channels. * currently ignoring single bit channels. */ -- cgit v1.2.3 From ea0a59f80650c7bd7c72889f1c7bb72bfd3fdbd5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 10 Nov 2014 09:26:11 +0100 Subject: HMC5883: Reduce output, add indices to make back-tracking lines easier, remove output completely for an OK-operation (the driver is NOT the right place to talk to the user!) --- src/drivers/hmc5883/hmc5883.cpp | 49 +++++++++++++---------------------------- 1 file changed, 15 insertions(+), 34 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index e4ecfa6b5..81f767965 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1049,11 +1049,9 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) * LSM/Ga, giving 1.16 and 1.08 */ float expected_cal[3] = { 1.16f, 1.08f, 1.08f }; - warnx("starting mag scale calibration"); - /* start the sensor polling at 50 Hz */ if (OK != ioctl(filp, SENSORIOCSPOLLRATE, 50)) { - warn("failed to set 2Hz poll rate"); + warn("FAILED: SENSORIOCSPOLLRATE 2Hz"); ret = 1; goto out; } @@ -1061,25 +1059,25 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) /* Set to 2.5 Gauss. We ask for 3 to get the right part of * the chained if statement above. */ if (OK != ioctl(filp, MAGIOCSRANGE, 3)) { - warnx("failed to set 2.5 Ga range"); + warnx("FAILED: MAGIOCSRANGE 3.3 Ga"); ret = 1; goto out; } if (OK != ioctl(filp, MAGIOCEXSTRAP, 1)) { - warnx("failed to enable sensor calibration mode"); + warnx("FAILED: MAGIOCEXSTRAP 1"); ret = 1; goto out; } if (OK != ioctl(filp, MAGIOCGSCALE, (long unsigned int)&mscale_previous)) { - warn("WARNING: failed to get scale / offsets for mag"); + warn("FAILED: MAGIOCGSCALE 1"); ret = 1; goto out; } if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_null)) { - warn("WARNING: failed to set null scale / offsets for mag"); + warn("FAILED: MAGIOCSSCALE 1"); ret = 1; goto out; } @@ -1094,7 +1092,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) ret = ::poll(&fds, 1, 2000); if (ret != 1) { - warn("timed out waiting for sensor data"); + warn("ERROR: TIMEOUT 1"); goto out; } @@ -1102,7 +1100,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) sz = ::read(fd, &report, sizeof(report)); if (sz != sizeof(report)) { - warn("periodic read failed"); + warn("ERROR: READ 1"); ret = -EIO; goto out; } @@ -1118,7 +1116,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) ret = ::poll(&fds, 1, 2000); if (ret != 1) { - warn("timed out waiting for sensor data"); + warn("ERROR: TIMEOUT 2"); goto out; } @@ -1126,7 +1124,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) sz = ::read(fd, &report, sizeof(report)); if (sz != sizeof(report)) { - warn("periodic read failed"); + warn("ERROR: READ 2"); ret = -EIO; goto out; } @@ -1142,33 +1140,19 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) sum_excited[1] += cal[1]; sum_excited[2] += cal[2]; } - - //warnx("periodic read %u", i); - //warnx("measurement: %.6f %.6f %.6f", (double)report.x, (double)report.y, (double)report.z); - //warnx("cal: %.6f %.6f %.6f", (double)cal[0], (double)cal[1], (double)cal[2]); } if (good_count < 5) { - warn("failed calibration"); ret = -EIO; goto out; } -#if 0 - warnx("measurement avg: %.6f %.6f %.6f", - (double)sum_excited[0]/good_count, - (double)sum_excited[1]/good_count, - (double)sum_excited[2]/good_count); -#endif - float scaling[3]; scaling[0] = sum_excited[0] / good_count; scaling[1] = sum_excited[1] / good_count; scaling[2] = sum_excited[2] / good_count; - warnx("axes scaling: %.6f %.6f %.6f", (double)scaling[0], (double)scaling[1], (double)scaling[2]); - /* set scaling in device */ mscale_previous.x_scale = scaling[0]; mscale_previous.y_scale = scaling[1]; @@ -1179,29 +1163,26 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) out: if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) { - warn("failed to set new scale / offsets for mag"); + warn("FAILED: MAGIOCSSCALE 2"); } /* set back to normal mode */ /* Set to 1.1 Gauss */ if (OK != ::ioctl(fd, MAGIOCSRANGE, 1)) { - warnx("failed to set 1.1 Ga range"); + warnx("FAILED: MAGIOCSRANGE 1.1 Ga"); } if (OK != ::ioctl(fd, MAGIOCEXSTRAP, 0)) { - warnx("failed to disable sensor calibration mode"); + warnx("FAILED: MAGIOCEXSTRAP 0"); } if (ret == OK) { - if (!check_scale()) { - warnx("mag scale calibration successfully finished."); - } else { - warnx("mag scale calibration finished with invalid results."); + if (check_scale()) { + /* failed */ + warnx("FAILED: SCALE"); ret = ERROR; } - } else { - warnx("mag scale calibration failed."); } return ret; -- cgit v1.2.3 From d253c8ba7d9cfc408328afd7c3708892b23626c0 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:38:13 +1000 Subject: commander: correct the description array --- src/modules/commander/commander.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 46caddd46..1c3b68edd 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -760,7 +760,10 @@ int commander_thread_main(int argc, char *argv[]) nav_states_str[NAVIGATION_STATE_AUTO_MISSION] = "AUTO_MISSION"; nav_states_str[NAVIGATION_STATE_AUTO_LOITER] = "AUTO_LOITER"; nav_states_str[NAVIGATION_STATE_AUTO_RTL] = "AUTO_RTL"; + nav_states_str[NAVIGATION_STATE_AUTO_RCRECOVER] = "AUTO_RCRECOVER"; nav_states_str[NAVIGATION_STATE_AUTO_RTGS] = "AUTO_RTGS"; + nav_states_str[NAVIGATION_STATE_AUTO_LANDENGFAIL] = "AUTO_LANDENGFAIL"; + nav_states_str[NAVIGATION_STATE_AUTO_LANDGPSFAIL] = "AUTO_LANDGPSFAIL"; nav_states_str[NAVIGATION_STATE_ACRO] = "ACRO"; nav_states_str[NAVIGATION_STATE_LAND] = "LAND"; nav_states_str[NAVIGATION_STATE_DESCEND] = "DESCEND"; -- cgit v1.2.3 From f7db91ac32d6db1fbef9aa0c868636561bd2282c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:38:46 +1000 Subject: commander: enhance the failsafe verbose output --- src/modules/commander/commander.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 1c3b68edd..f9ea4e914 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1851,7 +1851,11 @@ int commander_thread_main(int argc, char *argv[]) if (status.failsafe != failsafe_old) { status_changed = true; - mavlink_log_info(mavlink_fd, "[cmd] failsafe state: %i", status.failsafe); + if (status.failsafe) { + mavlink_log_info(mavlink_fd, "[cmd] failsafe on"); + } else { + mavlink_log_info(mavlink_fd, "[cmd] failsafe off"); + } failsafe_old = status.failsafe; } -- cgit v1.2.3 From f8bed3cd892157b2db147b0d6a60f26371acdeb8 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:39:35 +1000 Subject: state_machine_helper: whitespace --- src/modules/commander/state_machine_helper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 9568752ae..a49965efd 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -444,7 +444,7 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, * Check failsafe and main status and set navigation status for navigator accordingly */ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished, - const bool stay_in_failsafe) + const bool stay_in_failsafe) { navigation_state_t nav_state_old = status->nav_state; -- cgit v1.2.3 From 2c577815818b579743dab13ef0055f02605699d1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:40:13 +1000 Subject: state_machine_helper: trying to clean up some failsafe logic --- src/modules/commander/state_machine_helper.cpp | 43 ++++++++++++++++++-------- 1 file changed, 30 insertions(+), 13 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index a49965efd..3553dcdc3 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -497,11 +497,14 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en break; case MAIN_STATE_AUTO_MISSION: + /* go into failsafe * - if commanded to do so * - if we have an engine failure - * - if either the datalink is enabled and lost as well as RC is lost - * - if there is no datalink and the mission is finished */ + * - if the datalink is enabled and lost as well as RC is lost + * or if the datalink is disabled and lost as well as RC is lost and the mission is finished */ + + /* first look at the commands */ if (status->engine_failure_cmd) { status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL; } else if (status->data_link_lost_cmd) { @@ -509,14 +512,16 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en } else if (status->gps_failure_cmd) { status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL; } else if (status->rc_signal_lost_cmd) { - status->nav_state = NAVIGATION_STATE_AUTO_RTGS; //XXX - /* Finished handling commands which have priority , now handle failures */ + status->nav_state = NAVIGATION_STATE_AUTO_RCRECOVER; + + /* finished handling commands which have priority, now handle failures */ } else if (status->gps_failure) { status->nav_state = NAVIGATION_STATE_AUTO_LANDGPSFAIL; } else if (status->engine_failure) { status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL; - } else if (((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) || - (!data_link_loss_enabled && status->rc_signal_lost && mission_finished)) { + + /* check for RC signal and datalink lost (with datalink enabled) after mission is finished */ + } else if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) { status->failsafe = true; if (status->condition_global_position_valid && status->condition_home_position_valid) { @@ -529,7 +534,21 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* also go into failsafe if just datalink is lost */ + /* check if RC signal is lost (with dataink disabled) after mission is finished*/ + } else if (!data_link_loss_enabled && status->rc_signal_lost && mission_finished) { + status->failsafe = true; + + if (status->condition_global_position_valid && status->condition_home_position_valid) { + status->nav_state = NAVIGATION_STATE_AUTO_RCRECOVER; + } else if (status->condition_local_position_valid) { + status->nav_state = NAVIGATION_STATE_LAND; + } else if (status->condition_local_altitude_valid) { + status->nav_state = NAVIGATION_STATE_DESCEND; + } else { + status->nav_state = NAVIGATION_STATE_TERMINATION; + } + + /* also go into failsafe if just datalink is lost (with datalink enabled) */ } else if (status->data_link_lost && data_link_loss_enabled) { status->failsafe = true; @@ -543,13 +562,11 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* don't bother if RC is lost and mission is not yet finished */ - } else if (status->rc_signal_lost && !stay_in_failsafe) { + /* stay where you are */ + } else if (stay_in_failsafe){ - /* this mode is ok, we don't need RC for missions */ - status->nav_state = NAVIGATION_STATE_AUTO_MISSION; - } else if (!stay_in_failsafe){ - /* everything is perfect */ + /* everything is perfect */ + } else { status->nav_state = NAVIGATION_STATE_AUTO_MISSION; } break; -- cgit v1.2.3 From f1d56cbddc575115215f680ba42cdedde40b2626 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:41:41 +1000 Subject: navigator: don't reset the finished flag, this fixes the strange problem where it toggles between MISSION and RTL --- src/modules/navigator/navigator_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index a867dd0da..eff3a5938 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -632,7 +632,6 @@ Navigator::publish_mission_result() } /* reset reached bool */ _mission_result.reached = false; - _mission_result.finished = false; } void -- cgit v1.2.3 From 89724c24a16bd340c33c27531435089e7bd338fb Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 10 Nov 2014 21:42:13 +1000 Subject: vehicle_status: whitespace --- src/modules/uORB/topics/vehicle_status.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h index a1b2667e3..91491c148 100644 --- a/src/modules/uORB/topics/vehicle_status.h +++ b/src/modules/uORB/topics/vehicle_status.h @@ -108,7 +108,7 @@ typedef enum { NAVIGATION_STATE_AUTO_LANDGPSFAIL, /**< Auto land on gps failure (e.g. open loop loiter down) */ NAVIGATION_STATE_ACRO, /**< Acro mode */ NAVIGATION_STATE_LAND, /**< Land mode */ - NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */ + NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */ NAVIGATION_STATE_TERMINATION, /**< Termination mode */ NAVIGATION_STATE_OFFBOARD, NAVIGATION_STATE_MAX, -- cgit v1.2.3 From d15203de91cc07530809060f949374bb8918daea Mon Sep 17 00:00:00 2001 From: mazahner Date: Mon, 10 Nov 2014 17:35:48 +0100 Subject: Debug/NuttX: small changes to make it work with the current stable branch. Debug/NuttX made existing code work with python3 in gdb. Added some new features --- Debug/NuttX | 38 +++-- Debug/Nuttx.py | 433 ++++++++++++++++++++++++++++++++++++++++++++++++++------- 2 files changed, 416 insertions(+), 55 deletions(-) diff --git a/Debug/NuttX b/Debug/NuttX index d34e9f5b4..4b9f4b5a1 100644 --- a/Debug/NuttX +++ b/Debug/NuttX @@ -78,7 +78,7 @@ end ################################################################################ define showfiles - set $task = (struct _TCB *)$arg0 + set $task = (struct tcb_s *)$arg0 set $nfiles = sizeof((*(struct filelist*)0).fl_files) / sizeof(struct file) printf "%d files\n", $nfiles set $index = 0 @@ -102,7 +102,7 @@ end ################################################################################ define _showtask_oneline - set $task = (struct _TCB *)$arg0 + set $task = (struct tcb_s *)$arg0 printf " %p %.2d %.3d %s\n", $task, $task->pid, $task->sched_priority, $task->name end @@ -139,7 +139,7 @@ end # Print task registers for a NuttX v7em target with FPU enabled. # define _showtaskregs_v7em - set $task = (struct _TCB *)$arg0 + set $task = (struct tcb_s *)$arg0 set $regs = (uint32_t *)&($task->xcp.regs[0]) printf " r0: 0x%08x 0x%08x 0x%08x 0x%08x 0x%08x 0x%08x 0x%08x 0x%08x\n", $regs[27], $regs[28], $regs[29], $regs[30], $regs[2], $regs[3], $regs[4], $regs[5] @@ -162,7 +162,7 @@ end define _showsemaphore printf "count %d ", $arg0->semcount if $arg0->holder.htcb != 0 - set $_task = (struct _TCB *)$arg0->holder.htcb + set $_task = (struct tcb_s *)$arg0->holder.htcb printf "held by %s", $_task->name end printf "\n" @@ -172,7 +172,7 @@ end # Print information about a task's stack usage # define showtaskstack - set $task = (struct _TCB *)$arg0 + set $task = (struct tcb_s *)$arg0 if $task == &g_idletcb printf "can't measure idle stack\n" @@ -189,7 +189,7 @@ end # Print details of a task # define showtask - set $task = (struct _TCB *)$arg0 + set $task = (struct tcb_s *)$arg0 printf "%p %.2d ", $task, $task->pid _showtaskstate $task @@ -204,7 +204,7 @@ define showtask if $task->task_state != TSTATE_TASK_RUNNING _showtaskregs_v7em $task else - _showcurrentregs_v7em + _showtaskregs_v7em $task end # XXX print registers here @@ -247,8 +247,10 @@ define showtasks _showtasklist &g_pendingtasks printf "RUNNABLE\n" _showtasklist &g_readytorun - printf "WAITING\n" + printf "WAITING for Semaphore\n" _showtasklist &g_waitingforsemaphore + printf "WAITING for Signal\n" + _showtasklist &g_waitingforsignal printf "INACTIVE\n" _showtasklist &g_inactivetasks end @@ -257,3 +259,23 @@ document showtasks . showtasks . Print a list of all tasks in the system, separated into their respective queues. end + +define my_mem + + set $start = $arg0 + set $end = $arg1 + set $cursor = $start + + if $start < $end + while $cursor != $end + set *$cursor = 0x0000 + set $cursor = $cursor + 4 + printf "0x%x of 0x%x\n",$cursor,$end + end + else + while $cursor != $end + set *$cursor = 0x0000 + set $cursor = $cursor - 4 + end + end +end \ No newline at end of file diff --git a/Debug/Nuttx.py b/Debug/Nuttx.py index 7cc21b99f..cf86dd668 100644 --- a/Debug/Nuttx.py +++ b/Debug/Nuttx.py @@ -59,30 +59,42 @@ class NX_register_set(object): def __init__(self, xcpt_regs): if xcpt_regs is None: - self.regs['R0'] = long(gdb.parse_and_eval('$r0')) - self.regs['R1'] = long(gdb.parse_and_eval('$r1')) - self.regs['R2'] = long(gdb.parse_and_eval('$r2')) - self.regs['R3'] = long(gdb.parse_and_eval('$r3')) - self.regs['R4'] = long(gdb.parse_and_eval('$r4')) - self.regs['R5'] = long(gdb.parse_and_eval('$r5')) - self.regs['R6'] = long(gdb.parse_and_eval('$r6')) - self.regs['R7'] = long(gdb.parse_and_eval('$r7')) - self.regs['R8'] = long(gdb.parse_and_eval('$r8')) - self.regs['R9'] = long(gdb.parse_and_eval('$r9')) - self.regs['R10'] = long(gdb.parse_and_eval('$r10')) - self.regs['R11'] = long(gdb.parse_and_eval('$r11')) - self.regs['R12'] = long(gdb.parse_and_eval('$r12')) - self.regs['R13'] = long(gdb.parse_and_eval('$r13')) - self.regs['SP'] = long(gdb.parse_and_eval('$sp')) - self.regs['R14'] = long(gdb.parse_and_eval('$r14')) - self.regs['LR'] = long(gdb.parse_and_eval('$lr')) - self.regs['R15'] = long(gdb.parse_and_eval('$r15')) - self.regs['PC'] = long(gdb.parse_and_eval('$pc')) - self.regs['XPSR'] = long(gdb.parse_and_eval('$xpsr')) + self.regs['R0'] = self.mon_reg_call('r0') + self.regs['R1'] = self.mon_reg_call('r1') + self.regs['R2'] = self.mon_reg_call('r2') + self.regs['R3'] = self.mon_reg_call('r3') + self.regs['R4'] = self.mon_reg_call('r4') + self.regs['R5'] = self.mon_reg_call('r5') + self.regs['R6'] = self.mon_reg_call('r6') + self.regs['R7'] = self.mon_reg_call('r7') + self.regs['R8'] = self.mon_reg_call('r8') + self.regs['R9'] = self.mon_reg_call('r9') + self.regs['R10'] = self.mon_reg_call('r10') + self.regs['R11'] = self.mon_reg_call('r11') + self.regs['R12'] = self.mon_reg_call('r12') + self.regs['R13'] = self.mon_reg_call('r13') + self.regs['SP'] = self.mon_reg_call('sp') + self.regs['R14'] = self.mon_reg_call('r14') + self.regs['LR'] = self.mon_reg_call('lr') + self.regs['R15'] = self.mon_reg_call('r15') + self.regs['PC'] = self.mon_reg_call('pc') + self.regs['XPSR'] = self.mon_reg_call('xPSR') else: for key in self.v7em_regmap.keys(): self.regs[key] = int(xcpt_regs[self.v7em_regmap[key]]) + def mon_reg_call(self,register): + """ + register is the register as a string e.g. 'pc' + return integer containing the value of the register + """ + str_to_eval = "mon reg "+register + resp = gdb.execute(str_to_eval,to_string = True) + content = resp.split()[-1]; + try: + return int(content,16) + except: + return 0 @classmethod def with_xcpt_regs(cls, xcpt_regs): @@ -172,7 +184,7 @@ class NX_task(object): self.__dict__['stack_used'] = 0 else: stack_limit = self._tcb['adj_stack_size'] - for offset in range(0, stack_limit): + for offset in range(0, int(stack_limit)): if stack_base[offset] != 0xff: break self.__dict__['stack_used'] = stack_limit - offset @@ -187,7 +199,7 @@ class NX_task(object): def state(self): """return the name of the task's current state""" statenames = gdb.types.make_enum_dict(gdb.lookup_type('enum tstate_e')) - for name,value in statenames.iteritems(): + for name,value in statenames.items(): if value == self._tcb['task_state']: return name return 'UNKNOWN' @@ -196,16 +208,19 @@ class NX_task(object): def waiting_for(self): """return a description of what the task is waiting for, if it is waiting""" if self._state_is('TSTATE_WAIT_SEM'): - waitsem = self._tcb['waitsem'].dereference() - waitsem_holder = waitsem['holder'] - holder = NX_task.for_tcb(waitsem_holder['htcb']) - if holder is not None: - return '{}({})'.format(waitsem.address, holder.name) - else: - return '{}()'.format(waitsem.address) + try: + waitsem = self._tcb['waitsem'].dereference() + waitsem_holder = waitsem['holder'] + holder = NX_task.for_tcb(waitsem_holder['htcb']) + if holder is not None: + return '{}({})'.format(waitsem.address, holder.name) + else: + return '{}()'.format(waitsem.address) + except: + return 'EXCEPTION' if self._state_is('TSTATE_WAIT_SIG'): return 'signal' - return None + return "" @property def is_waiting(self): @@ -229,7 +244,7 @@ class NX_task(object): filearray = filelist['fl_files'] result = dict() for i in range(filearray.type.range()[0],filearray.type.range()[1]): - inode = long(filearray[i]['f_inode']) + inode = int(filearray[i]['f_inode']) if inode != 0: result[i] = inode return result @@ -253,7 +268,18 @@ class NX_task(object): def __str__(self): return "{}:{}".format(self.pid, self.name) - + + def showoff(self): + print("-------") + print(self.pid,end = ", ") + print(self.name,end = ", ") + print(self.state,end = ", ") + print(self.waiting_for,end = ", ") + print(self.stack_used,end = ", ") + print(self._tcb['adj_stack_size'],end = ", ") + print(self.file_descriptors) + print(self.registers) + def __format__(self, format_spec): return format_spec.format( pid = self.pid, @@ -265,7 +291,7 @@ class NX_task(object): file_descriptors = self.file_descriptors, registers = self.registers ) - + class NX_show_task (gdb.Command): """(NuttX) prints information about a task""" @@ -285,7 +311,7 @@ class NX_show_task (gdb.Command): my_fmt += ' R8 {registers[R8]:#010x} {registers[R9]:#010x} {registers[R10]:#010x} {registers[R11]:#010x}\n' my_fmt += ' R12 {registers[PC]:#010x}\n' my_fmt += ' SP {registers[SP]:#010x} LR {registers[LR]:#010x} PC {registers[PC]:#010x} XPSR {registers[XPSR]:#010x}\n' - print format(t, my_fmt) + print(format(t, my_fmt)) class NX_show_tasks (gdb.Command): """(NuttX) prints a list of tasks""" @@ -295,8 +321,10 @@ class NX_show_tasks (gdb.Command): def invoke(self, args, from_tty): tasks = NX_task.tasks() + print ('Number of tasks: ' + str(len(tasks))) for t in tasks: - print format(t, '{pid:<2} {name:<16} {state:<20} {stack_used:>4}/{stack_limit:<4}') + #t.showoff() + print(format(t, 'Task: {pid} {name} {state} {stack_used}/{stack_limit}')) NX_show_task() NX_show_tasks() @@ -306,15 +334,15 @@ class NX_show_heap (gdb.Command): def __init__(self): super(NX_show_heap, self).__init__('show heap', gdb.COMMAND_USER) - struct_mm_allocnode_s = gdb.lookup_type('struct mm_allocnode_s') - preceding_size = struct_mm_allocnode_s['preceding'].type.sizeof - if preceding_size == 2: + struct_mm_allocnode_s = gdb.lookup_type('struct mm_allocnode_s') + preceding_size = struct_mm_allocnode_s['preceding'].type.sizeof + if preceding_size == 2: self._allocflag = 0x8000 - elif preceding_size == 4: + elif preceding_size == 4: self._allocflag = 0x80000000 - else: - raise gdb.GdbError('invalid mm_allocnode_s.preceding size %u' % preceding_size) - self._allocnodesize = struct_mm_allocnode_s.sizeof + else: + raise gdb.GdbError('invalid mm_allocnode_s.preceding size %u' % preceding_size) + self._allocnodesize = struct_mm_allocnode_s.sizeof def _node_allocated(self, allocnode): if allocnode['preceding'] & self._allocflag: @@ -328,7 +356,7 @@ class NX_show_heap (gdb.Command): if region_start >= region_end: raise gdb.GdbError('heap region {} corrupt'.format(hex(region_start))) nodecount = region_end - region_start - print 'heap {} - {}'.format(region_start, region_end) + print ('heap {} - {}'.format(region_start, region_end)) cursor = 1 while cursor < nodecount: allocnode = region_start[cursor] @@ -336,8 +364,8 @@ class NX_show_heap (gdb.Command): state = '' else: state = '(free)' - print ' {} {} {}'.format(allocnode.address + self._allocnodesize, - self._node_size(allocnode), state) + print( ' {} {} {}'.format(allocnode.address + self._allocnodesize, + self._node_size(allocnode), state)) cursor += self._node_size(allocnode) / self._allocnodesize def invoke(self, args, from_tty): @@ -345,7 +373,7 @@ class NX_show_heap (gdb.Command): nregions = heap['mm_nregions'] region_starts = heap['mm_heapstart'] region_ends = heap['mm_heapend'] - print '{} heap(s)'.format(nregions) + print( '{} heap(s)'.format(nregions)) # walk the heaps for i in range(0, nregions): self._print_allocations(region_starts[i], region_ends[i]) @@ -370,6 +398,317 @@ class NX_show_interrupted_thread (gdb.Command): my_fmt += ' R8 {registers[R8]:#010x} {registers[R9]:#010x} {registers[R10]:#010x} {registers[R11]:#010x}\n' my_fmt += ' R12 {registers[PC]:#010x}\n' my_fmt += ' SP {registers[SP]:#010x} LR {registers[LR]:#010x} PC {registers[PC]:#010x} XPSR {registers[XPSR]:#010x}\n' - print format(registers, my_fmt) + print (format(registers, my_fmt)) NX_show_interrupted_thread() + +class NX_check_tcb(gdb.Command): + """ check the tcb of a task from a address """ + def __init__(self): + super(NX_check_tcb,self).__init__('show tcb', gdb.COMMAND_USER) + + def invoke(self,args,sth): + tasks = NX_task.tasks() + print("tcb int: ",int(args)) + print(tasks[int(args)]._tcb) + a =tasks[int(args)]._tcb['xcp']['regs'] + print("relevant registers:") + for reg in regmap: + hex_addr= hex(int(a[regmap[reg]])) + eval_string = 'info line *'+str(hex_addr) + print(reg,": ",hex_addr,) +NX_check_tcb() + +class NX_tcb(object): + def __init__(self): + pass + + def is_in(self,arg,list): + for i in list: + if arg == i: + return True; + return False + + def find_tcb_list(self,dq_entry_t): + tcb_list = [] + tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) + first_tcb = tcb_ptr.dereference() + tcb_list.append(first_tcb); + next_tcb = first_tcb['flink'].dereference() + while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + tcb_list.append(next_tcb); + old_tcb = next_tcb; + next_tcb = old_tcb['flink'].dereference() + + return [t for t in tcb_list if int(t['pid'])<2000] + + def getTCB(self): + list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] + tcb_list = []; + for l in list_of_listsnames: + li = gdb.lookup_global_symbol(l) + print(li) + cursor = li.value()['head'] + tcb_list = tcb_list + self.find_tcb_list(cursor) + +class NX_check_stack_order(gdb.Command): + """ Check the Stack order corresponding to the tasks """ + + def __init__(self): + super(NX_check_stack_order,self).__init__('show check_stack', gdb.COMMAND_USER) + + def is_in(self,arg,list): + for i in list: + if arg == i: + return True; + return False + + def find_tcb_list(self,dq_entry_t): + tcb_list = [] + tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) + first_tcb = tcb_ptr.dereference() + tcb_list.append(first_tcb); + next_tcb = first_tcb['flink'].dereference() + while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + tcb_list.append(next_tcb); + old_tcb = next_tcb; + next_tcb = old_tcb['flink'].dereference() + + return [t for t in tcb_list if int(t['pid'])<2000] + + def getTCB(self): + list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] + tcb_list = []; + for l in list_of_listsnames: + li = gdb.lookup_global_symbol(l) + cursor = li.value()['head'] + tcb_list = tcb_list + self.find_tcb_list(cursor) + return tcb_list + + def getSPfromTask(self,tcb): + regmap = NX_register_set.v7em_regmap + a =tcb['xcp']['regs'] + return int(a[regmap['SP']]) + + def find_closest(self,list,val): + tmp_list = [abs(i-val) for i in list] + tmp_min = min(tmp_list) + idx = tmp_list.index(tmp_min) + return idx,list[idx] + + def find_next_stack(self,address,_dict_in): + add_list = [] + name_list = [] + for key in _dict_in.keys(): + for i in range(3): + if _dict_in[key][i] < address: + add_list.append(_dict_in[key][i]) + if i == 2: # the last one is the processes stack pointer + name_list.append(self.check_name(key)+"_SP") + else: + name_list.append(self.check_name(key)) + + idx,new_address = self.find_closest(add_list,address) + return new_address,name_list[idx] + + def check_name(self,name): + if isinstance(name,(list)): + name = name[0]; + idx = name.find("\\") + newname = name[:idx] + + return newname + + def invoke(self,args,sth): + tcb = self.getTCB(); + stackadresses={}; + for t in tcb: + p = []; + #print(t.name,t._tcb['stack_alloc_ptr']) + p.append(int(t['stack_alloc_ptr'])) + p.append(int(t['adj_stack_ptr'])) + p.append(self.getSPfromTask(t)) + stackadresses[str(t['name'])] = p; + address = int("0x30000000",0) + print("stack address : process") + for i in range(len(stackadresses)*3): + address,name = self.find_next_stack(address,stackadresses) + print(hex(address),": ",name) + +NX_check_stack_order() + +class NX_run_debug_util(gdb.Command): + """ show the registers of a task corresponding to a tcb address""" + def __init__(self): + super(NX_run_debug_util,self).__init__('show regs', gdb.COMMAND_USER) + + def printRegisters(self,task): + regmap = NX_register_set.v7em_regmap + a =task._tcb['xcp']['regs'] + print("relevant registers in ",task.name,":") + for reg in regmap: + hex_addr= hex(int(a[regmap[reg]])) + eval_string = 'info line *'+str(hex_addr) + print(reg,": ",hex_addr,) + + def getPCfromTask(self,task): + regmap = NX_register_set.v7em_regmap + a =task._tcb['xcp']['regs'] + return hex(int(a[regmap['PC']])) + + def invoke(self,args,sth): + tasks = NX_task.tasks() + if args == '': + for t in tasks: + self.printRegisters(t) + eval_str = "list *"+str(self.getPCfromTask(t)) + print("this is the location in code where the current threads $pc is:") + gdb.execute(eval_str) + else: + tcb_nr = int(args); + print("tcb_nr = ",tcb_nr) + t = tasks[tcb_nr] + self.printRegisters(t) + eval_str = "list *"+str(self.getPCfromTask(t)) + print("this is the location in code where the current threads $pc is:") + gdb.execute(eval_str) + +NX_run_debug_util() + + +class NX_search_tcb(gdb.Command): + """ shot PID's of all running tasks """ + + def __init__(self): + super(NX_search_tcb,self).__init__('show alltcb', gdb.COMMAND_USER) + + def is_in(self,arg,list): + for i in list: + if arg == i: + return True; + return False + + def find_tcb_list(self,dq_entry_t): + tcb_list = [] + tcb_ptr = dq_entry_t.cast(gdb.lookup_type('struct tcb_s').pointer()) + first_tcb = tcb_ptr.dereference() + tcb_list.append(first_tcb); + next_tcb = first_tcb['flink'].dereference() + while not self.is_in(int(next_tcb['pid']),[int(t['pid']) for t in tcb_list]): + tcb_list.append(next_tcb); + old_tcb = next_tcb; + next_tcb = old_tcb['flink'].dereference() + + return [t for t in tcb_list if int(t['pid'])<2000] + + def invoke(self,args,sth): + list_of_listsnames = ['g_pendingtasks','g_readytorun','g_waitingforsemaphore','g_waitingforsignal','g_inactivetasks'] + tasks = []; + for l in list_of_listsnames: + li = gdb.lookup_global_symbol(l) + cursor = li.value()['head'] + tasks = tasks + self.find_tcb_list(cursor) + + # filter for tasks that are listed twice + tasks_filt = {} + for t in tasks: + pid = int(t['pid']); + if not pid in tasks_filt.keys(): + tasks_filt[pid] = t['name']; + print('{num_t} Tasks found:'.format(num_t = len(tasks_filt))) + for pid in tasks_filt.keys(): + print("PID: ",pid," ",tasks_filt[pid]) + +NX_search_tcb() + + +class NX_my_bt(gdb.Command): + """ 'fake' backtrace: backtrace the stack of a process and check every suspicious address for the list + arg: tcb_address$ + (can easily be found by typing 'showtask'). + """ + + def __init__(self): + super(NX_my_bt,self).__init__('show mybt', gdb.COMMAND_USER) + + def readmem(self,addr): + ''' + read memory at addr and return nr + ''' + str_to_eval = "x/x "+hex(addr) + resp = gdb.execute(str_to_eval,to_string = True) + idx = resp.find('\t') + return int(resp[idx:],16) + + def is_in_bounds(self,val): + lower_bound = int("08004000",16) + upper_bound = int("080ae0c0",16); + #print(lower_bound," ",val," ",upper_bound) + if val>lower_bound and val0: + name = words[3][idx+1:]; + path = words[3][:idx]; + else: + name = words[3]; + path = ""; + block = gdb.block_for_pc(addr) + func = block.function + if str(func) == "None": + func = block.superblock.function + + if valid: + print("Line: ",line," in ",path,"/",name,"in ",func) + return name,path,line,func + + + + + def invoke(self,args,sth): + addr_dec = int(args[2:],16) + _tcb = self.get_tcb_from_address(addr_dec) + print("found task with PID: ",_tcb["pid"]) + up_stack = int(_tcb['adj_stack_ptr']) + curr_sp = int(_tcb['xcp']['regs'][0]) #curr stack pointer + other_sp = int(_tcb['xcp']['regs'][8]) # other stack pointer + stacksize = int(_tcb['adj_stack_size']) # other stack pointer + + print("tasks current SP = ",hex(curr_sp),"stack max ptr is at ",hex(up_stack)) + + if curr_sp == up_stack: + sp = other_sp + else: + sp = curr_sp; + + while(sp < up_stack): + mem = self.readmem(sp) + #print(hex(sp)," : ",hex(mem)) + if self.is_in_bounds(mem): + # this is a potential instruction ptr + stack_percentage = (up_stack-sp)/stacksize + name,path,line,func = self.print_instruction_at(mem,stack_percentage) + sp = sp + 4; # jump up one word + +NX_my_bt() -- cgit v1.2.3 From 88093ebf1af5483d8b5c218adb1ea0c4798ee21e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 10 Nov 2014 18:52:18 +0100 Subject: Hotfix: Fix IO channel mapping --- src/drivers/px4io/px4io.cpp | 47 +++++++++++++++++++++++---------------------- 1 file changed, 24 insertions(+), 23 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 6d68d9f60..06faf49a4 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1245,41 +1245,42 @@ PX4IO::io_set_rc_config() * for compatibility reasons with existing * autopilots / GCS'. */ - param_get(param_find("RC_MAP_ROLL"), &ichan); - - /* subtract one from 1-based index - this might be - * a negative number now - */ - ichan -= 1; - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan] = 0; + /* ROLL */ + param_get(param_find("RC_MAP_ROLL"), &ichan); + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { + input_map[ichan - 1] = 0; + } + /* PITCH */ param_get(param_find("RC_MAP_PITCH"), &ichan); + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { + input_map[ichan - 1] = 1; + } - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan] = 1; - + /* YAW */ param_get(param_find("RC_MAP_YAW"), &ichan); + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { + input_map[ichan - 1] = 2; + } - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan] = 2; - + /* THROTTLE */ param_get(param_find("RC_MAP_THROTTLE"), &ichan); + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { + input_map[ichan - 1] = 3; + } - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan] = 3; - + /* FLAPS */ param_get(param_find("RC_MAP_FLAPS"), &ichan); + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { + input_map[ichan - 1] = 4; + } - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) - input_map[ichan] = 4; - + /* MAIN MODE SWITCH */ param_get(param_find("RC_MAP_MODE_SW"), &ichan); - - if ((ichan >= 0) && (ichan < (int)_max_rc_input)) { + if ((ichan > 0) && (ichan <= (int)_max_rc_input)) { /* use out of normal bounds index to indicate special channel */ - input_map[ichan] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH; + input_map[ichan - 1] = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH; } /* -- cgit v1.2.3 From c8a8305326f84cdfd92326b36241caee64b0c529 Mon Sep 17 00:00:00 2001 From: fludwig Date: Wed, 15 Oct 2014 23:48:40 +0200 Subject: added switch to send PWM to Brushless Controller in unarmed state --- ROMFS/px4fmu_common/init.d/3030_io_camflyer | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/3030_io_camflyer b/ROMFS/px4fmu_common/init.d/3030_io_camflyer index 83c470234..0f0cb3a89 100644 --- a/ROMFS/px4fmu_common/init.d/3030_io_camflyer +++ b/ROMFS/px4fmu_common/init.d/3030_io_camflyer @@ -3,3 +3,6 @@ sh /etc/init.d/rc.fw_defaults set MIXER FMU_Q +# Provide ESC a constant 1000 us pulse while disarmed +set PWM_OUTPUTS 4 +set PWM_DISARMED 1000 -- cgit v1.2.3 From e474600978f0fe92de79622a746d06f2c9df77a9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Nov 2014 09:18:31 +1000 Subject: commander: make the failsafe message critical --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index f9ea4e914..002a33811 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1852,9 +1852,9 @@ int commander_thread_main(int argc, char *argv[]) if (status.failsafe != failsafe_old) { status_changed = true; if (status.failsafe) { - mavlink_log_info(mavlink_fd, "[cmd] failsafe on"); + mavlink_log_critical(mavlink_fd, "failsafe mode on"); } else { - mavlink_log_info(mavlink_fd, "[cmd] failsafe off"); + mavlink_log_critical(mavlink_fd, "failsafe mode off"); } failsafe_old = status.failsafe; } -- cgit v1.2.3 From fa5f3658828280f54a7fec3c33ec3e25e4198561 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Nov 2014 10:25:53 +1000 Subject: state_machine_helper: fixed comments --- src/modules/commander/state_machine_helper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 3553dcdc3..e1a626262 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -520,7 +520,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en } else if (status->engine_failure) { status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL; - /* check for RC signal and datalink lost (with datalink enabled) after mission is finished */ + /* check for RC signal and datalink lost (with datalink enabled) */ } else if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) { status->failsafe = true; @@ -534,7 +534,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* check if RC signal is lost (with dataink disabled) after mission is finished*/ + /* check if RC signal is lost (with datalink disabled) after mission is finished */ } else if (!data_link_loss_enabled && status->rc_signal_lost && mission_finished) { status->failsafe = true; -- cgit v1.2.3 From 3c9a73f3e41a379e5e7bbf6e98d67facc3b2b49f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Nov 2014 10:28:24 +1000 Subject: fixed empty if body --- src/modules/commander/state_machine_helper.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index e1a626262..a9a5c4051 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -562,11 +562,8 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* stay where you are */ - } else if (stay_in_failsafe){ - - /* everything is perfect */ - } else { + /* stay where you are if you should stay in failsafe, otherwise everything is perfect */ + } else if (!stay_in_failsafe){ status->nav_state = NAVIGATION_STATE_AUTO_MISSION; } break; -- cgit v1.2.3 From d98831c3b50addab0084f9636060cece46ff92bc Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Nov 2014 10:42:26 +1000 Subject: navigator: move waypoint reached reset to a more obvious location --- src/modules/navigator/mission.cpp | 1 + src/modules/navigator/navigator_main.cpp | 2 -- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 7fac69a61..b8e3274fd 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -707,6 +707,7 @@ Mission::set_mission_item_reached() _navigator->get_mission_result()->reached = true; _navigator->get_mission_result()->seq_reached = _current_offboard_mission_index; _navigator->publish_mission_result(); + reset_mission_item_reached(); } void diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index eff3a5938..e933919fb 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -630,8 +630,6 @@ Navigator::publish_mission_result() /* advertise and publish */ _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result); } - /* reset reached bool */ - _mission_result.reached = false; } void -- cgit v1.2.3 From 51ffb887c39ecfd0cb94879475f032ee65505321 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Tue, 11 Nov 2014 11:13:08 +0100 Subject: UAVCAN: initialize device id for mag and baro to allow DEVIOCGDEVICEID ioctl to return useful data --- src/drivers/device/device.h | 3 ++- src/modules/uavcan/sensors/mag.cpp | 2 ++ src/modules/uavcan/sensors/sensor_bridge.cpp | 3 +++ src/modules/uavcan/sensors/sensor_bridge.hpp | 2 ++ 4 files changed, 9 insertions(+), 1 deletion(-) diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index 9d684e394..67aaa0aff 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -130,7 +130,8 @@ public: enum DeviceBusType { DeviceBusType_UNKNOWN = 0, DeviceBusType_I2C = 1, - DeviceBusType_SPI = 2 + DeviceBusType_SPI = 2, + DeviceBusType_UAVCAN = 3, }; /* diff --git a/src/modules/uavcan/sensors/mag.cpp b/src/modules/uavcan/sensors/mag.cpp index 8e6a9a22f..0d9ea08c5 100644 --- a/src/modules/uavcan/sensors/mag.cpp +++ b/src/modules/uavcan/sensors/mag.cpp @@ -49,6 +49,8 @@ UavcanMagnetometerBridge::UavcanMagnetometerBridge(uavcan::INode& node) : UavcanCDevSensorBridgeBase("uavcan_mag", "/dev/uavcan/mag", MAG_DEVICE_PATH, MAG_TOPICS), _sub_mag(node) { + _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883; + _scale.x_scale = 1.0F; _scale.y_scale = 1.0F; _scale.z_scale = 1.0F; diff --git a/src/modules/uavcan/sensors/sensor_bridge.cpp b/src/modules/uavcan/sensors/sensor_bridge.cpp index 9608ce680..0999938fc 100644 --- a/src/modules/uavcan/sensors/sensor_bridge.cpp +++ b/src/modules/uavcan/sensors/sensor_bridge.cpp @@ -103,6 +103,9 @@ void UavcanCDevSensorBridgeBase::publish(const int node_id, const void *report) return; } + // update device id as we now know our device node_id + _device_id.devid_s.address = static_cast(node_id); + // Ask the CDev helper which class instance we can take const int class_instance = register_class_devname(_class_devname); if (class_instance < 0 || class_instance >= int(_max_channels)) { diff --git a/src/modules/uavcan/sensors/sensor_bridge.hpp b/src/modules/uavcan/sensors/sensor_bridge.hpp index 1316f7ecc..04c59b77d 100644 --- a/src/modules/uavcan/sensors/sensor_bridge.hpp +++ b/src/modules/uavcan/sensors/sensor_bridge.hpp @@ -112,6 +112,8 @@ protected: _channels(new Channel[MaxChannels]) { memcpy(_orb_topics, orb_topics, sizeof(orb_id_t) * MaxChannels); + _device_id.devid_s.bus_type = DeviceBusType_UAVCAN; + _device_id.devid_s.bus = 1; // @TBD: insert UAVCAN bus no. here } /** -- cgit v1.2.3 From cf2baac516b6f86daf30342be47264b2dcc8abc4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 11 Nov 2014 21:45:13 +1000 Subject: navigator: more reset reached calls --- src/modules/navigator/datalinkloss.cpp | 4 ++++ src/modules/navigator/rcloss.cpp | 2 ++ 2 files changed, 6 insertions(+) diff --git a/src/modules/navigator/datalinkloss.cpp b/src/modules/navigator/datalinkloss.cpp index 66f1c8c73..e789fd10d 100644 --- a/src/modules/navigator/datalinkloss.cpp +++ b/src/modules/navigator/datalinkloss.cpp @@ -156,6 +156,7 @@ DataLinkLoss::set_dll_item() /* Request flight termination from the commander */ _navigator->get_mission_result()->flight_termination = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); warnx("not switched to manual: request flight termination"); pos_sp_triplet->previous.valid = false; pos_sp_triplet->current.valid = false; @@ -188,6 +189,7 @@ DataLinkLoss::advance_dll() mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: too many DL losses, fly to airfield home"); _navigator->get_mission_result()->stay_in_failsafe = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP; } else { if (!_param_skipcommshold.get()) { @@ -208,6 +210,7 @@ DataLinkLoss::advance_dll() _dll_state = DLL_STATE_FLYTOAIRFIELDHOMEWP; _navigator->get_mission_result()->stay_in_failsafe = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); break; case DLL_STATE_FLYTOAIRFIELDHOMEWP: _dll_state = DLL_STATE_TERMINATE; @@ -215,6 +218,7 @@ DataLinkLoss::advance_dll() mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no manual control, terminating"); _navigator->get_mission_result()->stay_in_failsafe = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); break; case DLL_STATE_TERMINATE: warnx("dll end"); diff --git a/src/modules/navigator/rcloss.cpp b/src/modules/navigator/rcloss.cpp index 5564a1c42..42392e739 100644 --- a/src/modules/navigator/rcloss.cpp +++ b/src/modules/navigator/rcloss.cpp @@ -163,6 +163,7 @@ RCLoss::advance_rcl() _rcl_state = RCL_STATE_TERMINATE; _navigator->get_mission_result()->stay_in_failsafe = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); } break; case RCL_STATE_LOITER: @@ -171,6 +172,7 @@ RCLoss::advance_rcl() mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RC not regained, terminating"); _navigator->get_mission_result()->stay_in_failsafe = true; _navigator->publish_mission_result(); + reset_mission_item_reached(); break; case RCL_STATE_TERMINATE: warnx("rcl end"); -- cgit v1.2.3 From 1394b02c2e2158b2796a51ca622c17893f78361f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 11 Nov 2014 13:45:25 +0100 Subject: Make tools executable --- Documentation/versionfilter.sh | 0 Tools/px_generate_xml.sh | 0 Tools/px_update_wiki.sh | 0 3 files changed, 0 insertions(+), 0 deletions(-) mode change 100644 => 100755 Documentation/versionfilter.sh mode change 100644 => 100755 Tools/px_generate_xml.sh mode change 100644 => 100755 Tools/px_update_wiki.sh diff --git a/Documentation/versionfilter.sh b/Documentation/versionfilter.sh old mode 100644 new mode 100755 diff --git a/Tools/px_generate_xml.sh b/Tools/px_generate_xml.sh old mode 100644 new mode 100755 diff --git a/Tools/px_update_wiki.sh b/Tools/px_update_wiki.sh old mode 100644 new mode 100755 -- cgit v1.2.3 From 50b410664f4087bb4fd50e8bba62267c70719b71 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Tue, 11 Nov 2014 17:01:20 +0100 Subject: UAVCAN: set bus number part of device_id to zero --- src/modules/uavcan/sensors/sensor_bridge.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uavcan/sensors/sensor_bridge.hpp b/src/modules/uavcan/sensors/sensor_bridge.hpp index 04c59b77d..e31960537 100644 --- a/src/modules/uavcan/sensors/sensor_bridge.hpp +++ b/src/modules/uavcan/sensors/sensor_bridge.hpp @@ -113,7 +113,7 @@ protected: { memcpy(_orb_topics, orb_topics, sizeof(orb_id_t) * MaxChannels); _device_id.devid_s.bus_type = DeviceBusType_UAVCAN; - _device_id.devid_s.bus = 1; // @TBD: insert UAVCAN bus no. here + _device_id.devid_s.bus = 0; } /** -- cgit v1.2.3 From d63c054bb00a0df6666f498950ab797dc07817b4 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 09:48:32 +1000 Subject: state_machine_helper: changed failsafe behaviour: always require at least one link for default, do RTGS as soon as datalink is lost if datalink loss mode is enabled --- src/modules/commander/state_machine_helper.cpp | 29 ++++++++------------------ 1 file changed, 9 insertions(+), 20 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index a9a5c4051..e37019d02 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -501,8 +501,7 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en /* go into failsafe * - if commanded to do so * - if we have an engine failure - * - if the datalink is enabled and lost as well as RC is lost - * or if the datalink is disabled and lost as well as RC is lost and the mission is finished */ + * - depending on datalink, RC and if the mission is finished */ /* first look at the commands */ if (status->engine_failure_cmd) { @@ -520,8 +519,9 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en } else if (status->engine_failure) { status->nav_state = NAVIGATION_STATE_AUTO_LANDENGFAIL; - /* check for RC signal and datalink lost (with datalink enabled) */ - } else if ((status->data_link_lost && data_link_loss_enabled) && status->rc_signal_lost) { + /* datalink loss enabled: + * check for datalink lost: this should always trigger RTGS */ + } else if (data_link_loss_enabled && status->data_link_lost) { status->failsafe = true; if (status->condition_global_position_valid && status->condition_home_position_valid) { @@ -534,8 +534,11 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* check if RC signal is lost (with datalink disabled) after mission is finished */ - } else if (!data_link_loss_enabled && status->rc_signal_lost && mission_finished) { + /* datalink loss disabled: + * check if both, RC and datalink are lost during the mission + * or RC is lost after the mission is finished: this should always trigger RCRECOVER */ + } else if (!data_link_loss_enabled && ((status->rc_signal_lost && status->data_link_lost) || + (status->rc_signal_lost && mission_finished))) { status->failsafe = true; if (status->condition_global_position_valid && status->condition_home_position_valid) { @@ -548,20 +551,6 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en status->nav_state = NAVIGATION_STATE_TERMINATION; } - /* also go into failsafe if just datalink is lost (with datalink enabled) */ - } else if (status->data_link_lost && data_link_loss_enabled) { - status->failsafe = true; - - if (status->condition_global_position_valid && status->condition_home_position_valid) { - status->nav_state = NAVIGATION_STATE_AUTO_RTGS; - } else if (status->condition_local_position_valid) { - status->nav_state = NAVIGATION_STATE_LAND; - } else if (status->condition_local_altitude_valid) { - status->nav_state = NAVIGATION_STATE_DESCEND; - } else { - status->nav_state = NAVIGATION_STATE_TERMINATION; - } - /* stay where you are if you should stay in failsafe, otherwise everything is perfect */ } else if (!stay_in_failsafe){ status->nav_state = NAVIGATION_STATE_AUTO_MISSION; -- cgit v1.2.3 From 20703c8d2352dd137ec13be69e42fe6fdfd9f8f2 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 11:05:06 +1000 Subject: manual_control_setpoint: whitespace --- src/modules/uORB/topics/manual_control_setpoint.h | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h index dde237adc..c0c33a629 100644 --- a/src/modules/uORB/topics/manual_control_setpoint.h +++ b/src/modules/uORB/topics/manual_control_setpoint.h @@ -47,7 +47,7 @@ * Switch position */ typedef enum { - SWITCH_POS_NONE = 0, /**< switch is not mapped */ + SWITCH_POS_NONE = 0, /**< switch is not mapped */ SWITCH_POS_ON, /**< switch activated (value = 1) */ SWITCH_POS_MIDDLE, /**< middle position (value = 0) */ SWITCH_POS_OFF /**< switch not activated (value = -1) */ @@ -93,12 +93,12 @@ struct manual_control_setpoint_s { float aux4; /**< default function: camera roll */ float aux5; /**< default function: payload drop */ - switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */ - switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */ - switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */ - switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */ - switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */ - switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */ + switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */ + switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */ + switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */ + switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */ + switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */ + switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */ }; /**< manual control inputs */ /** -- cgit v1.2.3 From b1c6692f2028b616581efaf7a320a7cf7072a02f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 11:06:25 +1000 Subject: commander: removed unused definition --- src/modules/commander/commander.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 46caddd46..149c0f60e 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -220,8 +220,6 @@ void control_status_leds(vehicle_status_s *status, const actuator_armed_s *actua void check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *valid_out, bool *changed); -void check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_status_s *status); - transition_result_t set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoint_s *sp_man); void set_control_mode(); -- cgit v1.2.3 From f1058bdf0816cda718cee4d5a69c4ac3d53ea781 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 11:07:27 +1000 Subject: manual_control_setpoint: wrong comment --- src/modules/uORB/topics/manual_control_setpoint.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h index c0c33a629..50b7bd9e5 100644 --- a/src/modules/uORB/topics/manual_control_setpoint.h +++ b/src/modules/uORB/topics/manual_control_setpoint.h @@ -99,7 +99,7 @@ struct manual_control_setpoint_s { switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */ switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */ switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */ -}; /**< manual control inputs */ +}; /** * @} -- cgit v1.2.3 From 703fcec62d3430b75876d2c06183bbf4451f0dd6 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 12:11:23 +1000 Subject: navigator: fix do jumps: after the repetitions are completed the current mission index is no longer invalid --- src/modules/navigator/mission.cpp | 21 ++++++++++++--------- 1 file changed, 12 insertions(+), 9 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 7fac69a61..840c9ec0e 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -371,7 +371,7 @@ Mission::set_mission_items() } else { /* no mission available or mission finished, switch to loiter */ if (_mission_type != MISSION_TYPE_NONE) { - mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished, loitering"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished"); /* use last setpoint for loiter */ _navigator->set_can_loiter_at_sp(true); @@ -595,13 +595,14 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id); } - if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) { - /* mission item index out of bounds */ - return false; - } - /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */ for (int i = 0; i < 10; i++) { + + if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) { + /* mission item index out of bounds */ + return false; + } + const ssize_t len = sizeof(struct mission_item_s); /* read mission item to temp storage first to not overwrite current mission item if data damaged */ @@ -630,7 +631,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s /* not supposed to happen unless the datamanager can't access the * dataman */ mavlink_log_critical(_navigator->get_mavlink_fd(), - "ERROR DO JUMP waypoint could not be written"); + "ERROR DO JUMP waypoint could not be written"); return false; } } @@ -639,8 +640,10 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_index_ptr = mission_item_tmp.do_jump_mission_index; } else { - mavlink_log_critical(_navigator->get_mavlink_fd(), - "DO JUMP repetitions completed"); + if (is_current) { + mavlink_log_critical(_navigator->get_mavlink_fd(), + "DO JUMP repetitions completed"); + } /* no more DO_JUMPS, therefore just try to continue with next mission item */ (*mission_index_ptr)++; } -- cgit v1.2.3 From 08443205e90955c13532c79aa02a283a50cce25d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 13:07:06 +1000 Subject: navigator: make DO_JUMPS survive power on resets --- src/modules/navigator/mission.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 840c9ec0e..cfe85c84e 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -627,7 +627,8 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s if (is_current) { (mission_item_tmp.do_jump_current_count)++; /* save repeat count */ - if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, &mission_item_tmp, len) != len) { + if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_POWER_ON_RESET, + &mission_item_tmp, len) != len) { /* not supposed to happen unless the datamanager can't access the * dataman */ mavlink_log_critical(_navigator->get_mavlink_fd(), -- cgit v1.2.3 From 14b5732c6eff6998d013c0816e983320906c462d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 13:26:10 +1000 Subject: px4flow: small verbose output fix --- src/drivers/px4flow/px4flow.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 6c68636c6..9e1ecb61e 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -76,7 +76,7 @@ #define PX4FLOW_BUS PX4_I2C_BUS_EXPANSION #define I2C_FLOW_ADDRESS 0x42 //* 7-bit address. 8-bit address is 0x84 //range 0x42 - 0x49 - + /* PX4FLOW Registers addresses */ #define PX4FLOW_REG 0x00 /* Measure Register */ @@ -443,7 +443,7 @@ PX4FLOW::measure() if (OK != ret) { perf_count(_comms_errors); log("i2c::transfer returned %d", ret); - printf("i2c::transfer flow returned %d"); + printf("i2c::transfer flow returned %d", ret); return ret; } -- cgit v1.2.3 From 7bc9a6257731a741ff309f060f6cf87c33c4a266 Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Wed, 12 Nov 2014 09:52:35 +0100 Subject: code style, warnings --- src/modules/uavcan/actuators/esc.cpp | 13 +++++++------ src/modules/uavcan/uavcan_main.cpp | 9 ++++----- src/systemcmds/motor_test/motor_test.c | 19 ++++++++----------- 3 files changed, 19 insertions(+), 22 deletions(-) diff --git a/src/modules/uavcan/actuators/esc.cpp b/src/modules/uavcan/actuators/esc.cpp index fbd4f0bcd..1d23099f3 100644 --- a/src/modules/uavcan/actuators/esc.cpp +++ b/src/modules/uavcan/actuators/esc.cpp @@ -113,8 +113,7 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) msg.cmd.push_back(static_cast(scaled)); _esc_status.esc[i].esc_setpoint_raw = abs(static_cast(scaled)); - } - else { + } else { msg.cmd.push_back(static_cast(0)); } } @@ -128,18 +127,20 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) void UavcanEscController::arm_all_escs(bool arm) { - if (arm) + if (arm) { _armed_mask = -1; - else + } else { _armed_mask = 0; + } } void UavcanEscController::arm_single_esc(int num, bool arm) { - if (arm) + if (arm) { _armed_mask = MOTOR_BIT(num); - else + } else { _armed_mask = 0; + } } void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure &msg) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 653d4f98c..2c543462e 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -346,13 +346,12 @@ int UavcanNode::run() // can we mix? if (_test_in_progress) { - float outputs[NUM_ACTUATOR_OUTPUTS] = {}; - outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f; + float test_outputs[NUM_ACTUATOR_OUTPUTS] = {}; + test_outputs[_test_motor.motor_number] = _test_motor.value*2.0f-1.0f; // Output to the bus - _esc_controller.update_outputs(outputs, NUM_ACTUATOR_OUTPUTS); - } - else if (controls_updated && (_mixers != nullptr)) { + _esc_controller.update_outputs(test_outputs, NUM_ACTUATOR_OUTPUTS); + } else if (controls_updated && (_mixers != nullptr)) { // XXX one output group has 8 outputs max, // but this driver could well serve multiple groups. diff --git a/src/systemcmds/motor_test/motor_test.c b/src/systemcmds/motor_test/motor_test.c index 079f99674..087699b05 100644 --- a/src/systemcmds/motor_test/motor_test.c +++ b/src/systemcmds/motor_test/motor_test.c @@ -67,19 +67,15 @@ void motor_test(unsigned channel, float value) _test_motor.timestamp = hrt_absolute_time(); _test_motor.value = value; - if (_test_motor_pub > 0) { - /* publish armed state */ - orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor); - } else { - /* advertise and publish */ - _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor); - } + _test_motor_pub = orb_advertise(ORB_ID(test_motor), &_test_motor); + orb_publish(ORB_ID(test_motor), _test_motor_pub, &_test_motor); } static void usage(const char *reason) { - if (reason != NULL) + if (reason != NULL) { warnx("%s", reason); + } errx(1, "usage:\n" @@ -90,8 +86,9 @@ static void usage(const char *reason) int motor_test_main(int argc, char *argv[]) { - unsigned long channel, lval; - float value; + unsigned long channel = 0; + unsigned long lval; + float value = 0.0f; int ch; if (argc != 5) { @@ -122,7 +119,7 @@ int motor_test_main(int argc, char *argv[]) motor_test(channel, value); - printf("motor %d set to %.2f\n", channel, value); + printf("motor %d set to %.2f\n", channel, (double)value); exit(0); } -- cgit v1.2.3 From 64de403b5f2aa4af57918510451373424c162b68 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 12 Nov 2014 20:06:49 +1000 Subject: navigator: trying to improve a comment --- src/modules/navigator/mission.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index cfe85c84e..d0611b9e5 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -595,7 +595,8 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id); } - /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */ + /* Repeat this several times in case there are several DO JUMPS that we need to follow along, however, after + * 10 iterations we have to assume that the DO JUMPS are probably cycling and give up. */ for (int i = 0; i < 10; i++) { if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) { -- cgit v1.2.3 From ae99a179ac0fd2b7a240d51adf7d992ff91ed598 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Nov 2014 12:21:15 +0100 Subject: Include NuttX sscanf() fix --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 5ee4b2b2c..47a94a097 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 5ee4b2b2c26bbc35d1669840f0676e8aa383b984 +Subproject commit 47a94a0979fd5aee2c8416e0197d6ce5926e94ca -- cgit v1.2.3 From d7ebea6ec2f3783bfdd4becd7cda5fd24c340a85 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Nov 2014 09:01:00 +0100 Subject: Fix comparison in upload script for test builds --- Tools/upload.sh | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/upload.sh b/Tools/upload.sh index 17d87fe61..c0dd65eba 100755 --- a/Tools/upload.sh +++ b/Tools/upload.sh @@ -10,17 +10,17 @@ SYSTYPE=`uname -s` # # XXX The uploader should be smarter than this. # -if [ $SYSTYPE=Darwin ]; +if [ $SYSTYPE = "Darwin" ]; then SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*" fi -if [ $SYSTYPE=Linux ]; +if [ $SYSTYPE = "Linux" ]; then SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*" fi -if [ $SYSTYPE="" ]; +if [ $SYSTYPE = "" ]; then SERIAL_PORTS="COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0" fi -- cgit v1.2.3 From afcbab7fba84cf3d3d016a63fbca405ade15889a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Nov 2014 13:37:58 +0100 Subject: PX4FLOW driver: Prevent sensor from spamming the system on errors. Use the perf system call to look at error counters. --- src/drivers/px4flow/px4flow.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4flow/px4flow.cpp b/src/drivers/px4flow/px4flow.cpp index 9e1ecb61e..804027b05 100644 --- a/src/drivers/px4flow/px4flow.cpp +++ b/src/drivers/px4flow/px4flow.cpp @@ -200,7 +200,7 @@ PX4FLOW::PX4FLOW(int bus, int address) : _buffer_overflows(perf_alloc(PC_COUNT, "px4flow_buffer_overflows")) { // enable debug() calls - _debug_enabled = true; + _debug_enabled = false; // work_cancel in the dtor will explode if we don't do this... memset(&_work, 0, sizeof(_work)); @@ -240,7 +240,7 @@ PX4FLOW::init() _px4flow_topic = orb_advertise(ORB_ID(optical_flow), &zero_report); if (_px4flow_topic < 0) { - debug("failed to create px4flow object. Did you start uOrb?"); + warnx("failed to create px4flow object. Did you start uOrb?"); } ret = OK; @@ -442,8 +442,6 @@ PX4FLOW::measure() if (OK != ret) { perf_count(_comms_errors); - log("i2c::transfer returned %d", ret); - printf("i2c::transfer flow returned %d", ret); return ret; } @@ -465,7 +463,7 @@ PX4FLOW::collect() ret = transfer(nullptr, 0, &val[0], 22); if (ret < 0) { - log("error reading from sensor: %d", ret); + debug("error reading from sensor: %d", ret); perf_count(_comms_errors); perf_end(_sample_perf); return ret; @@ -565,7 +563,7 @@ PX4FLOW::cycle() /* perform collection */ if (OK != collect()) { - log("collection error"); + debug("collection error"); /* restart the measurement state machine */ start(); return; @@ -592,7 +590,7 @@ PX4FLOW::cycle() /* measurement phase */ if (OK != measure()) { - log("measure error"); + debug("measure error"); } /* next phase is collection */ -- cgit v1.2.3 From 826fd3f4cdf492be1e5b05f7da4493ff10118876 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 13 Nov 2014 09:43:51 +1000 Subject: commander: reordering navigation states to match enum --- src/modules/commander/commander.cpp | 153 +++++++++++++++++++----------------- 1 file changed, 83 insertions(+), 70 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 7917bc9f2..3307c4bfc 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -2201,18 +2201,6 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; - case NAVIGATION_STATE_ACRO: - control_mode.flag_control_manual_enabled = true; - control_mode.flag_control_auto_enabled = false; - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; - control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; - control_mode.flag_control_termination_enabled = false; - break; - case NAVIGATION_STATE_ALTCTL: control_mode.flag_control_manual_enabled = true; control_mode.flag_control_auto_enabled = false; @@ -2225,64 +2213,6 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; - case NAVIGATION_STATE_OFFBOARD: - control_mode.flag_control_manual_enabled = false; - control_mode.flag_control_auto_enabled = false; - control_mode.flag_control_offboard_enabled = true; - - switch (sp_offboard.mode) { - case OFFBOARD_CONTROL_MODE_DIRECT_RATES: - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; - control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; - break; - - case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = true; - control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; - break; - - case OFFBOARD_CONTROL_MODE_DIRECT_FORCE: - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; - control_mode.flag_control_force_enabled = true; - control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; - break; - - case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED: - case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED: - case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED: - case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED: - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = true; - control_mode.flag_control_altitude_enabled = true; - control_mode.flag_control_climb_rate_enabled = true; - control_mode.flag_control_position_enabled = true; - control_mode.flag_control_velocity_enabled = true; - //XXX: the flags could depend on sp_offboard.ignore - break; - - default: - control_mode.flag_control_rates_enabled = false; - control_mode.flag_control_attitude_enabled = false; - control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; - } - - break; - case NAVIGATION_STATE_POSCTL: control_mode.flag_control_manual_enabled = true; control_mode.flag_control_auto_enabled = false; @@ -2323,6 +2253,19 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; + case NAVIGATION_STATE_ACRO: + control_mode.flag_control_manual_enabled = true; + control_mode.flag_control_auto_enabled = false; + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + control_mode.flag_control_termination_enabled = false; + break; + + case NAVIGATION_STATE_LAND: control_mode.flag_control_manual_enabled = false; control_mode.flag_control_auto_enabled = true; @@ -2336,6 +2279,19 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; + case NAVIGATION_STATE_DESCEND: + /* TODO: check if this makes sense */ + control_mode.flag_control_manual_enabled = false; + control_mode.flag_control_auto_enabled = true; + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = true; + control_mode.flag_control_termination_enabled = false; + break; + case NAVIGATION_STATE_TERMINATION: /* disable all controllers on termination */ control_mode.flag_control_manual_enabled = false; @@ -2349,6 +2305,63 @@ set_control_mode() control_mode.flag_control_termination_enabled = true; break; + case NAVIGATION_STATE_OFFBOARD: + control_mode.flag_control_manual_enabled = false; + control_mode.flag_control_auto_enabled = false; + control_mode.flag_control_offboard_enabled = true; + + switch (sp_offboard.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + break; + + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + break; + + case OFFBOARD_CONTROL_MODE_DIRECT_FORCE: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_force_enabled = true; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + break; + + case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_NED: + case OFFBOARD_CONTROL_MODE_DIRECT_LOCAL_OFFSET_NED: + case OFFBOARD_CONTROL_MODE_DIRECT_BODY_NED: + case OFFBOARD_CONTROL_MODE_DIRECT_BODY_OFFSET_NED: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_altitude_enabled = true; + control_mode.flag_control_climb_rate_enabled = true; + control_mode.flag_control_position_enabled = true; + control_mode.flag_control_velocity_enabled = true; + //XXX: the flags could depend on sp_offboard.ignore + break; + + default: + control_mode.flag_control_rates_enabled = false; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + } + break; + default: break; } -- cgit v1.2.3 From 00cc2d55111fe6dcf03fc847aa6e65204e4a0a2c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 13 Nov 2014 09:44:17 +1000 Subject: commander: added navstate RCRECOVER which was missing --- src/modules/commander/commander.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 3307c4bfc..5c4ad26f4 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -2225,9 +2225,11 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; + case NAVIGATION_STATE_AUTO_MISSION: case NAVIGATION_STATE_AUTO_LOITER: case NAVIGATION_STATE_AUTO_RTL: + case NAVIGATION_STATE_AUTO_RCRECOVER: case NAVIGATION_STATE_AUTO_RTGS: case NAVIGATION_STATE_AUTO_LANDENGFAIL: control_mode.flag_control_manual_enabled = false; -- cgit v1.2.3 From db3f2fc94621ee13c7ec22d5fef1dd5ae74a0742 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 13 Nov 2014 09:46:12 +1000 Subject: commander: whitespace --- src/modules/commander/commander.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 5c4ad26f4..ec173c12b 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -2225,7 +2225,6 @@ set_control_mode() control_mode.flag_control_termination_enabled = false; break; - case NAVIGATION_STATE_AUTO_MISSION: case NAVIGATION_STATE_AUTO_LOITER: case NAVIGATION_STATE_AUTO_RTL: -- cgit v1.2.3 From 6a543b1d0154d7da9ddb4123df1479cf01aa88bc Mon Sep 17 00:00:00 2001 From: Holger Steinhaus Date: Thu, 13 Nov 2014 10:45:32 +0100 Subject: build fix --- src/modules/uORB/topics/test_motor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/test_motor.h b/src/modules/uORB/topics/test_motor.h index c880fe099..2dd90e69d 100644 --- a/src/modules/uORB/topics/test_motor.h +++ b/src/modules/uORB/topics/test_motor.h @@ -57,7 +57,7 @@ struct test_motor_s { uint64_t timestamp; /**< output timestamp in us since system boot */ unsigned motor_number; /**< number of motor to spin */ - float value; /**< output power, range [0..1] + float value; /**< output power, range [0..1] */ }; /** -- cgit v1.2.3 From 71d7659b4870c0cff4a7f542e262cff33c588f30 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 11:51:21 +0100 Subject: Updated NuttX, only comment changes --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 47a94a097..9d06b6457 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 47a94a0979fd5aee2c8416e0197d6ce5926e94ca +Subproject commit 9d06b645790e1445f14e3b19c71d40b3088f4e4f -- cgit v1.2.3 From 780451dd65db72aa28b75ddad2effbbba8db8626 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:48:30 +0100 Subject: Remove unneeded file --- ROMFS/px4fmu_common/init.d/rc.jig | 10 ---------- 1 file changed, 10 deletions(-) delete mode 100644 ROMFS/px4fmu_common/init.d/rc.jig diff --git a/ROMFS/px4fmu_common/init.d/rc.jig b/ROMFS/px4fmu_common/init.d/rc.jig deleted file mode 100644 index e2b5d8f30..000000000 --- a/ROMFS/px4fmu_common/init.d/rc.jig +++ /dev/null @@ -1,10 +0,0 @@ -#!nsh -# -# Test jig startup script -# - -echo "[testing] doing production test.." - -tests jig - -echo "[testing] testing done" -- cgit v1.2.3 From 4bcb2697415009279bd481eb9d22f015846147f1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:48:49 +0100 Subject: Add capability to read chip ID and revision from ver command --- src/systemcmds/ver/ver.c | 85 +++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 84 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 9ae080ee2..b11b593c3 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -53,13 +53,38 @@ static const char sz_ver_bdate_str[] = "bdate"; static const char sz_ver_gcc_str[] = "gcc"; static const char sz_ver_all_str[] = "all"; +#ifdef CONFIG_ARCH_CHIP_STM32 +#include + +static const char mcu_ver_str[] = "mcu"; + +#define DBGMCU_IDCODE 0xE0042000 + +#define STM32F40x_41x 0x413 +#define STM32F42x_43x 0x419 + +#define REVID_MASK 0xFFFF0000 +#define DEVID_MASK 0xFFF + +/* magic numbers from reference manual */ +enum STM32F4_REV { + STM32F4_REV_A = 0x1000, + STM32F4_REV_Z = 0x1001, + STM32F4_REV_Y = 0x1003, + STM32F4_REV_1 = 0x1007, + STM32F4_REV_3 = 0x2001 +}; +#else +#error stm32 +#endif + static void usage(const char *reason) { if (reason != NULL) { printf("%s\n", reason); } - printf("usage: ver {hw|hwcmp|git|bdate|gcc|all}\n\n"); + printf("usage: ver {hw|hwcmp|git|bdate|gcc|all|mcu}\n\n"); } __EXPORT int ver_main(int argc, char *argv[]); @@ -107,6 +132,64 @@ int ver_main(int argc, char *argv[]) printf("GCC toolchain: %s\n", __VERSION__); ret = 0; +#ifdef CONFIG_ARCH_CHIP_STM32 + } else if (!strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { + uint32_t abc = getreg32(DBGMCU_IDCODE); + + uint32_t chip_version = abc & DEVID_MASK; + enum STM32F4_REV revid = (abc & REVID_MASK) >> 16; + + printf("CHIP TYPE: "); + + switch (revid) { + case STM32F40x_41x: + printf("STM32F40x"); + break; + case STM32F42x_43x: + printf("STM32F42x"); + break; + default: + printf("STM32F???"); + break; + } + + char rev; + + switch (chip_version) { + + case STM32F4_REV_A: + rev = 'A'; + break; + case STM32F4_REV_Z: + rev = 'Z'; + break; + case STM32F4_REV_Y: + rev = 'Y'; + break; + case STM32F4_REV_1: + rev = '1'; + break; + case STM32F4_REV_3: + rev = '3'; + break; + default: + rev = '?'; + break; + } + + printf("\nHW REV: %c\n", rev); + + if (rev < STM32F4_REV_3) { + printf("\n\nWARNING WARNING WARNING!\n" + "Revision %c has a silicon errata\n" + "on USB connectivity combined with\n" + "flash bank #2. This device can only\n" + "utilize a maximum of 1MB flash safely!\n" + "http://px4.io/help/errata\n", rev); + } + ret = 0; +#endif + } else { errx(1, "unknown command.\n"); } -- cgit v1.2.3 From 8e8dd62fbd9906c980d9e88943a2fda5b90977e0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:49:06 +0100 Subject: Let the uploader print the binary size --- Tools/px_uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index d4e461226..3a4540ac0 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -458,7 +458,7 @@ if os.path.exists("/usr/sbin/ModemManager"): # Load the firmware file fw = firmware(args.firmware) -print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'))) +print("Loaded firmware for %x,%x, size: %d bytes, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'))) print("If the board does not respond within 1-2 seconds, unplug and re-plug the USB connector.") # Spin waiting for a device to show up -- cgit v1.2.3 From a7eaf07f4f9d6df54b7602c07ce7fbdf2db700f9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:49:48 +0100 Subject: Motor test: optimize for size --- src/systemcmds/motor_test/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/systemcmds/motor_test/module.mk b/src/systemcmds/motor_test/module.mk index eb36d2ded..261428ef9 100644 --- a/src/systemcmds/motor_test/module.mk +++ b/src/systemcmds/motor_test/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = motor_test SRCS = motor_test.c MODULE_STACKSIZE = 4096 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From d4a5f345aabc83506b05277b9dcf71e24700c70d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:50:38 +0100 Subject: Remove unneeded apps from build --- makefiles/config_px4fmu-v2_default.mk | 17 +---------------- makefiles/config_px4fmu-v2_test.mk | 7 +++++++ 2 files changed, 8 insertions(+), 16 deletions(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index d17dff5bb..3c65b19e0 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -40,14 +40,8 @@ MODULES += drivers/meas_airspeed MODULES += drivers/frsky_telemetry MODULES += modules/sensors MODULES += drivers/mkblctrl -MODULES += drivers/pca8574 MODULES += drivers/px4flow - -# Needs to be burned to the ground and re-written; for now, -# just don't build it. -#MODULES += drivers/mkblctrl - # # System commands # @@ -61,7 +55,6 @@ MODULES += systemcmds/pwm MODULES += systemcmds/esc_calib MODULES += systemcmds/reboot MODULES += systemcmds/top -MODULES += systemcmds/tests MODULES += systemcmds/config MODULES += systemcmds/nshterm MODULES += systemcmds/mtd @@ -81,10 +74,8 @@ MODULES += modules/uavcan # Estimation modules (EKF/ SO3 / other filters) # MODULES += modules/attitude_estimator_ekf -MODULES += modules/attitude_estimator_so3 MODULES += modules/ekf_att_pos_estimator MODULES += modules/position_estimator_inav -MODULES += examples/flow_position_estimator # # Vehicle Control @@ -100,12 +91,6 @@ MODULES += modules/mc_pos_control # MODULES += modules/sdlog2 -# -# Unit tests -# -#MODULES += modules/unit_test -#MODULES += modules/commander/commander_tests - # # Library modules # @@ -139,7 +124,7 @@ MODULES += modules/bottle_drop #MODULES += examples/math_demo # Tutorial code from # https://pixhawk.ethz.ch/px4/dev/hello_sky -MODULES += examples/px4_simple_app +#MODULES += examples/px4_simple_app # Tutorial code from # https://pixhawk.ethz.ch/px4/dev/daemon diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index 2f4d9d6a4..6f54b960c 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -49,6 +49,13 @@ MODULES += lib/mathlib MODULES += lib/mathlib/math/filter MODULES += lib/conversion +# +# Modules to test-build, but not useful for test environment +# +MODULES += modules/attitude_estimator_so3 +MODULES += drivers/pca8574 +MODULES += examples/flow_position_estimator + # # Libraries # -- cgit v1.2.3 From 75bc8136b1d1d773a5664a226b5b766867fe5ff3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:50:56 +0100 Subject: Build NuttX optimized for size --- nuttx-configs/px4fmu-v1/nsh/Make.defs | 2 +- nuttx-configs/px4fmu-v2/nsh/Make.defs | 2 +- nuttx-configs/px4fmu-v2/scripts/ld.script | 3 ++- nuttx-configs/px4io-v1/nsh/Make.defs | 2 +- nuttx-configs/px4io-v2/nsh/Make.defs | 6 +----- 5 files changed, 6 insertions(+), 9 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs index 7b2ea703a..e7318e519 100644 --- a/nuttx-configs/px4fmu-v1/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs @@ -53,7 +53,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION = -Os ARCHCPUFLAGS = -mcpu=cortex-m4 \ -mthumb \ -march=armv7e-m \ diff --git a/nuttx-configs/px4fmu-v2/nsh/Make.defs b/nuttx-configs/px4fmu-v2/nsh/Make.defs index e70320aaa..f3ce53b4a 100644 --- a/nuttx-configs/px4fmu-v2/nsh/Make.defs +++ b/nuttx-configs/px4fmu-v2/nsh/Make.defs @@ -53,7 +53,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION = -Os ARCHCPUFLAGS = -mcpu=cortex-m4 \ -mthumb \ -march=armv7e-m \ diff --git a/nuttx-configs/px4fmu-v2/scripts/ld.script b/nuttx-configs/px4fmu-v2/scripts/ld.script index 1be39fb87..bec896d1c 100644 --- a/nuttx-configs/px4fmu-v2/scripts/ld.script +++ b/nuttx-configs/px4fmu-v2/scripts/ld.script @@ -50,7 +50,8 @@ MEMORY { - flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K + /* disabled due to silicon errata flash (rx) : ORIGIN = 0x08004000, LENGTH = 2032K */ + flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K } diff --git a/nuttx-configs/px4io-v1/nsh/Make.defs b/nuttx-configs/px4io-v1/nsh/Make.defs index 712631f47..7a0792ff6 100644 --- a/nuttx-configs/px4io-v1/nsh/Make.defs +++ b/nuttx-configs/px4io-v1/nsh/Make.defs @@ -53,7 +53,7 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION = -Os ARCHCPUFLAGS = -mcpu=cortex-m3 \ -mthumb \ -march=armv7-m diff --git a/nuttx-configs/px4io-v2/nsh/Make.defs b/nuttx-configs/px4io-v2/nsh/Make.defs index cd2d8eba3..1717464d2 100644 --- a/nuttx-configs/px4io-v2/nsh/Make.defs +++ b/nuttx-configs/px4io-v2/nsh/Make.defs @@ -53,15 +53,11 @@ NM = $(CROSSDEV)nm OBJCOPY = $(CROSSDEV)objcopy OBJDUMP = $(CROSSDEV)objdump -MAXOPTIMIZATION = -O3 +MAXOPTIMIZATION = -Os ARCHCPUFLAGS = -mcpu=cortex-m3 \ -mthumb \ -march=armv7-m -# enable precise stack overflow tracking -#INSTRUMENTATIONDEFINES = -finstrument-functions \ -# -ffixed-r10 - # use our linker script LDSCRIPT = ld.script -- cgit v1.2.3 From 3d2a5bae51763e5a542506383c9d97f95fc7d1ef Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:51:16 +0100 Subject: Board drivers: Optimize for size --- src/drivers/boards/aerocore/module.mk | 2 ++ src/drivers/boards/px4fmu-v1/module.mk | 2 ++ src/drivers/boards/px4fmu-v2/module.mk | 2 ++ src/drivers/boards/px4io-v1/module.mk | 2 ++ src/drivers/boards/px4io-v2/module.mk | 2 ++ 5 files changed, 10 insertions(+) diff --git a/src/drivers/boards/aerocore/module.mk b/src/drivers/boards/aerocore/module.mk index b53fe0a29..0a2d91009 100644 --- a/src/drivers/boards/aerocore/module.mk +++ b/src/drivers/boards/aerocore/module.mk @@ -6,3 +6,5 @@ SRCS = aerocore_init.c \ aerocore_pwm_servo.c \ aerocore_spi.c \ aerocore_led.c + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/boards/px4fmu-v1/module.mk b/src/drivers/boards/px4fmu-v1/module.mk index 66b776917..5e1a27d5a 100644 --- a/src/drivers/boards/px4fmu-v1/module.mk +++ b/src/drivers/boards/px4fmu-v1/module.mk @@ -8,3 +8,5 @@ SRCS = px4fmu_can.c \ px4fmu_spi.c \ px4fmu_usb.c \ px4fmu_led.c + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/boards/px4fmu-v2/module.mk b/src/drivers/boards/px4fmu-v2/module.mk index 99d37eeca..103232b0c 100644 --- a/src/drivers/boards/px4fmu-v2/module.mk +++ b/src/drivers/boards/px4fmu-v2/module.mk @@ -8,3 +8,5 @@ SRCS = px4fmu_can.c \ px4fmu_spi.c \ px4fmu_usb.c \ px4fmu2_led.c + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/boards/px4io-v1/module.mk b/src/drivers/boards/px4io-v1/module.mk index 2601a1c15..a7a14dd07 100644 --- a/src/drivers/boards/px4io-v1/module.mk +++ b/src/drivers/boards/px4io-v1/module.mk @@ -4,3 +4,5 @@ SRCS = px4io_init.c \ px4io_pwm_servo.c + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/boards/px4io-v2/module.mk b/src/drivers/boards/px4io-v2/module.mk index 85f94e8be..3f0e9a0b3 100644 --- a/src/drivers/boards/px4io-v2/module.mk +++ b/src/drivers/boards/px4io-v2/module.mk @@ -4,3 +4,5 @@ SRCS = px4iov2_init.c \ px4iov2_pwm_servo.c + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From c0f34dff2605381afacbec2bc1eba6b648daddd2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:51:33 +0100 Subject: STM32 drivers: Optimize for size --- src/drivers/stm32/adc/module.mk | 2 ++ src/drivers/stm32/module.mk | 2 ++ src/drivers/stm32/tone_alarm/module.mk | 2 ++ 3 files changed, 6 insertions(+) diff --git a/src/drivers/stm32/adc/module.mk b/src/drivers/stm32/adc/module.mk index 48620feea..38ea490a0 100644 --- a/src/drivers/stm32/adc/module.mk +++ b/src/drivers/stm32/adc/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = adc SRCS = adc.cpp INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/stm32/module.mk b/src/drivers/stm32/module.mk index bb751c7f6..54428e270 100644 --- a/src/drivers/stm32/module.mk +++ b/src/drivers/stm32/module.mk @@ -41,3 +41,5 @@ SRCS = drv_hrt.c \ drv_pwm_servo.c INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/stm32/tone_alarm/module.mk b/src/drivers/stm32/tone_alarm/module.mk index 827cf30b2..25a194ef6 100644 --- a/src/drivers/stm32/tone_alarm/module.mk +++ b/src/drivers/stm32/tone_alarm/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = tone_alarm SRCS = tone_alarm.cpp INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From f7f54062439f0b1c1208d0778f992f7052e1518b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:51:49 +0100 Subject: FMU driver: optimize for size --- src/drivers/px4fmu/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk index a60f1a434..a06323a52 100644 --- a/src/drivers/px4fmu/module.mk +++ b/src/drivers/px4fmu/module.mk @@ -8,3 +8,5 @@ SRCS = fmu.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From a12c98ba63c12ba08f1fb0f66df7b7079e444e1d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:52:08 +0100 Subject: Sensors: Optimize for size --- src/modules/sensors/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/sensors/module.mk b/src/modules/sensors/module.mk index 5b1bc5e86..dfbba92d9 100644 --- a/src/modules/sensors/module.mk +++ b/src/modules/sensors/module.mk @@ -42,3 +42,5 @@ SRCS = sensors.cpp \ sensor_params.c MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From a869105ba23394cfabb0a0000dd3b7fa3dc9fdb1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:52:34 +0100 Subject: Systemlib: Optimize for size --- src/modules/systemlib/module.mk | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index 147903aa0..5c4f2ec41 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -55,3 +55,4 @@ SRCS = err.c \ pwm_limit/pwm_limit.c \ circuit_breaker.c +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 54f296ce9d8245845a7a0bf32f5045a44aab40c7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:54:01 +0100 Subject: Sensor drivers: Optimize for size --- src/drivers/hmc5883/module.mk | 2 ++ src/drivers/l3gd20/module.mk | 2 ++ src/drivers/lsm303d/module.mk | 2 ++ src/drivers/mpu6000/module.mk | 2 ++ 4 files changed, 8 insertions(+) diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk index 5daa01dc5..be2ee7276 100644 --- a/src/drivers/hmc5883/module.mk +++ b/src/drivers/hmc5883/module.mk @@ -42,3 +42,5 @@ SRCS = hmc5883.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/l3gd20/module.mk b/src/drivers/l3gd20/module.mk index 5630e7aec..3d64d62be 100644 --- a/src/drivers/l3gd20/module.mk +++ b/src/drivers/l3gd20/module.mk @@ -8,3 +8,5 @@ SRCS = l3gd20.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk index b4f3974f4..0421eb113 100644 --- a/src/drivers/lsm303d/module.mk +++ b/src/drivers/lsm303d/module.mk @@ -8,3 +8,5 @@ SRCS = lsm303d.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk index 5b4893b12..da9fcc0fc 100644 --- a/src/drivers/mpu6000/module.mk +++ b/src/drivers/mpu6000/module.mk @@ -42,3 +42,5 @@ SRCS = mpu6000.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 32313a13dd1f98426f83b99310fc22b5adced37c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:54:16 +0100 Subject: PX4IO driver: Optimize for size --- src/drivers/px4io/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk index 5b838fb75..924283356 100644 --- a/src/drivers/px4io/module.mk +++ b/src/drivers/px4io/module.mk @@ -48,3 +48,5 @@ INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/com MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 42575bbc3763fe2b9e2d3e5b074ec74e4fc57f5a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:54:38 +0100 Subject: Bottle drop: Optimize for size --- src/modules/bottle_drop/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/bottle_drop/module.mk b/src/modules/bottle_drop/module.mk index 6b18fff55..960228879 100644 --- a/src/modules/bottle_drop/module.mk +++ b/src/modules/bottle_drop/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = bottle_drop SRCS = bottle_drop.cpp \ bottle_drop_params.c + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From a7bc52754de52ccbf0f958c20ce31408a8b4372e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 13:54:54 +0100 Subject: SDLOG2: Optimize for size --- src/modules/sdlog2/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/sdlog2/module.mk b/src/modules/sdlog2/module.mk index a28d43e72..d4a00af39 100644 --- a/src/modules/sdlog2/module.mk +++ b/src/modules/sdlog2/module.mk @@ -43,3 +43,5 @@ SRCS = sdlog2.c \ logbuffer.c MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 7b962e7d1bb6b60633c116b9d5395b24e6658664 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 14:17:24 +0100 Subject: Version command optimization --- src/systemcmds/ver/ver.c | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index b11b593c3..9d308bc3e 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -182,9 +182,7 @@ int ver_main(int argc, char *argv[]) if (rev < STM32F4_REV_3) { printf("\n\nWARNING WARNING WARNING!\n" "Revision %c has a silicon errata\n" - "on USB connectivity combined with\n" - "flash bank #2. This device can only\n" - "utilize a maximum of 1MB flash safely!\n" + "This device can only utilize a maximum of 1MB flash safely!\n" "http://px4.io/help/errata\n", rev); } ret = 0; -- cgit v1.2.3 From 2a37d274b142f49e250265eb14821d0b4f7e51cf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 15:51:55 +0100 Subject: Systemlib: Add MCU version command. ver commandline tool: Add support for MCU version command --- src/modules/systemlib/mcu_version.c | 109 ++++++++++++++++++++++++++++++++++++ src/modules/systemlib/mcu_version.h | 52 +++++++++++++++++ src/modules/systemlib/module.mk | 4 +- src/systemcmds/ver/ver.c | 88 ++++++----------------------- 4 files changed, 179 insertions(+), 74 deletions(-) create mode 100644 src/modules/systemlib/mcu_version.c create mode 100644 src/modules/systemlib/mcu_version.h diff --git a/src/modules/systemlib/mcu_version.c b/src/modules/systemlib/mcu_version.c new file mode 100644 index 000000000..4bcf95784 --- /dev/null +++ b/src/modules/systemlib/mcu_version.c @@ -0,0 +1,109 @@ +/**************************************************************************** + * + * 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 mcu_version.c + * + * Read out the microcontroller version from the board + * + * @author Lorenz Meier + * + */ + +#include "mcu_version.h" + +#include + +#ifdef CONFIG_ARCH_CHIP_STM32 +#include + +#define DBGMCU_IDCODE 0xE0042000 + +#define STM32F40x_41x 0x413 +#define STM32F42x_43x 0x419 + +#define REVID_MASK 0xFFFF0000 +#define DEVID_MASK 0xFFF + +#endif + + + +int mcu_version(char* rev, char** revstr) +{ +#ifdef CONFIG_ARCH_CHIP_STM32 + uint32_t abc = getreg32(DBGMCU_IDCODE); + + int32_t chip_version = abc & DEVID_MASK; + enum MCU_REV revid = (abc & REVID_MASK) >> 16; + + switch (chip_version) { + case STM32F40x_41x: + *revstr = "STM32F40x"; + break; + case STM32F42x_43x: + *revstr = "STM32F42x"; + break; + default: + *revstr = "STM32F???"; + break; + } + + switch (revid) { + + case MCU_REV_STM32F4_REV_A: + *rev = 'A'; + break; + case MCU_REV_STM32F4_REV_Z: + *rev = 'Z'; + break; + case MCU_REV_STM32F4_REV_Y: + *rev = 'Y'; + break; + case MCU_REV_STM32F4_REV_1: + *rev = '1'; + break; + case MCU_REV_STM32F4_REV_3: + *rev = '3'; + break; + default: + *rev = '?'; + revid = -1; + break; + } + + return revid; +#else + return -1; +#endif +} diff --git a/src/modules/systemlib/mcu_version.h b/src/modules/systemlib/mcu_version.h new file mode 100644 index 000000000..1b3d0aba9 --- /dev/null +++ b/src/modules/systemlib/mcu_version.h @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#pragma once + +/* magic numbers from reference manual */ +enum MCU_REV { + MCU_REV_STM32F4_REV_A = 0x1000, + MCU_REV_STM32F4_REV_Z = 0x1001, + MCU_REV_STM32F4_REV_Y = 0x1003, + MCU_REV_STM32F4_REV_1 = 0x1007, + MCU_REV_STM32F4_REV_3 = 0x2001 +}; + +/** + * Reports the microcontroller version of the main CPU. + * + * @param rev The silicon revision character + * @param revstr The full chip name string + * @return The silicon revision / version number as integer + */ +__EXPORT int mcu_version(char* rev, char** revstr); diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index 147903aa0..233023e25 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -53,5 +53,5 @@ SRCS = err.c \ otp.c \ board_serial.c \ pwm_limit/pwm_limit.c \ - circuit_breaker.c - + circuit_breaker.c \ + mcu_version.c diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 9d308bc3e..62a7a5b92 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -44,6 +44,7 @@ #include #include #include +#include // string constants for version commands static const char sz_ver_hw_str[] = "hw"; @@ -52,32 +53,8 @@ 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"; - -#ifdef CONFIG_ARCH_CHIP_STM32 -#include - static const char mcu_ver_str[] = "mcu"; -#define DBGMCU_IDCODE 0xE0042000 - -#define STM32F40x_41x 0x413 -#define STM32F42x_43x 0x419 - -#define REVID_MASK 0xFFFF0000 -#define DEVID_MASK 0xFFF - -/* magic numbers from reference manual */ -enum STM32F4_REV { - STM32F4_REV_A = 0x1000, - STM32F4_REV_Z = 0x1001, - STM32F4_REV_Y = 0x1003, - STM32F4_REV_1 = 0x1007, - STM32F4_REV_3 = 0x2001 -}; -#else -#error stm32 -#endif - static void usage(const char *reason) { if (reason != NULL) { @@ -132,61 +109,28 @@ int ver_main(int argc, char *argv[]) printf("GCC toolchain: %s\n", __VERSION__); ret = 0; -#ifdef CONFIG_ARCH_CHIP_STM32 + } else if (!strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { - uint32_t abc = getreg32(DBGMCU_IDCODE); - - uint32_t chip_version = abc & DEVID_MASK; - enum STM32F4_REV revid = (abc & REVID_MASK) >> 16; - - printf("CHIP TYPE: "); - - switch (revid) { - case STM32F40x_41x: - printf("STM32F40x"); - break; - case STM32F42x_43x: - printf("STM32F42x"); - break; - default: - printf("STM32F???"); - break; - } char rev; + char* revstr; - switch (chip_version) { - - case STM32F4_REV_A: - rev = 'A'; - break; - case STM32F4_REV_Z: - rev = 'Z'; - break; - case STM32F4_REV_Y: - rev = 'Y'; - break; - case STM32F4_REV_1: - rev = '1'; - break; - case STM32F4_REV_3: - rev = '3'; - break; - default: - rev = '?'; - break; - } + int chip_version = mcu_version(&rev, &revstr); + + if (chip_version < 0) { + printf("UNKNOWN MCU"); + ret = 1; - printf("\nHW REV: %c\n", rev); + } else { + printf("MCU: %s, rev. %c\n", revstr, rev); - if (rev < STM32F4_REV_3) { - printf("\n\nWARNING WARNING WARNING!\n" - "Revision %c has a silicon errata\n" - "This device can only utilize a maximum of 1MB flash safely!\n" - "http://px4.io/help/errata\n", rev); + if (chip_version < MCU_REV_STM32F4_REV_3) { + printf("\n\nWARNING WARNING WARNING!\n" + "Revision %c has a silicon errata\n" + "This device can only utilize a maximum of 1MB flash safely!\n" + "http://px4.io/help/errata\n", rev); + } } - ret = 0; -#endif } else { errx(1, "unknown command.\n"); -- cgit v1.2.3 From 6d59df1a5f67a58b6881d4d8a466082b847a2e61 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:19:51 +0100 Subject: Make ROMFS less chatty --- ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil | 8 ++------ ROMFS/px4fmu_common/init.d/10015_tbs_discovery | 2 +- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 2 +- ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d | 3 +-- ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil | 2 +- ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil | 2 +- .../px4fmu_common/init.d/1004_rc_fw_Rascal110.hil | 4 +--- ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil | 2 +- ROMFS/px4fmu_common/init.d/11001_hexa_cox | 4 ++-- ROMFS/px4fmu_common/init.d/12001_octo_cox | 2 +- ROMFS/px4fmu_common/init.d/3031_phantom | 4 +--- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 6 +----- ROMFS/px4fmu_common/init.d/3033_wingwing | 2 +- ROMFS/px4fmu_common/init.d/3034_fx79 | 2 +- ROMFS/px4fmu_common/init.d/3035_viper | 2 +- ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha | 8 ++------ ROMFS/px4fmu_common/init.d/4001_quad_x | 2 +- ROMFS/px4fmu_common/init.d/4008_ardrone | 3 --- ROMFS/px4fmu_common/init.d/4010_dji_f330 | 4 ++-- ROMFS/px4fmu_common/init.d/4011_dji_f450 | 4 ++-- ROMFS/px4fmu_common/init.d/4012_quad_x_can | 2 +- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 2 +- ROMFS/px4fmu_common/init.d/5001_quad_+ | 2 +- ROMFS/px4fmu_common/init.d/6001_hexa_x | 4 ++-- ROMFS/px4fmu_common/init.d/7001_hexa_+ | 4 ++-- ROMFS/px4fmu_common/init.d/8001_octo_x | 2 +- ROMFS/px4fmu_common/init.d/9001_octo_+ | 2 +- ROMFS/px4fmu_common/init.d/rc.autostart | 5 ++--- ROMFS/px4fmu_common/init.d/rc.sensors | 7 +------ ROMFS/px4fmu_common/init.d/rcS | 24 +++------------------- 30 files changed, 39 insertions(+), 83 deletions(-) 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 d114fe21a..4d6d350b8 100644 --- a/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil +++ b/ROMFS/px4fmu_common/init.d/1000_rc_fw_easystar.hil @@ -1,14 +1,10 @@ #!nsh # -# HILStar / X-Plane -# -# Lorenz Meier +# HILStar +# # sh /etc/init.d/rc.fw_defaults -echo "X Plane HIL starting.." - set HIL yes - set MIXER FMU_AERT diff --git a/ROMFS/px4fmu_common/init.d/10015_tbs_discovery b/ROMFS/px4fmu_common/init.d/10015_tbs_discovery index b1aa8c00b..c8379e3a1 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 , Thomas Gubler +# Anton Babushkin , Simon Wilks # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 3f47390c1..0b422de7e 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -2,7 +2,7 @@ # # 3DR Iris Quadcopter # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d index 6179855f6..a621de7ce 100644 --- a/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d +++ b/ROMFS/px4fmu_common/init.d/10017_steadidrone_qu4d @@ -2,8 +2,7 @@ # # Steadidrone QU4D # -# Thomas Gubler -# Lorenz Meier +# Thomas Gubler # sh /etc/init.d/rc.mc_defaults 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 7a7a9542c..1c4f6803b 100644 --- a/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil +++ b/ROMFS/px4fmu_common/init.d/1001_rc_quad_x.hil @@ -2,7 +2,7 @@ # # HIL Quadcopter X # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil index c47500c7a..0cbdd75be 100644 --- a/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil +++ b/ROMFS/px4fmu_common/init.d/1003_rc_quad_+.hil @@ -2,7 +2,7 @@ # # HIL Quadcopter + # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults 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 4e3e18326..fb440d2fc 100644 --- a/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil +++ b/ROMFS/px4fmu_common/init.d/1004_rc_fw_Rascal110.hil @@ -2,13 +2,11 @@ # # HIL Rascal 110 (Flightgear) # -# Thomas Gubler +# Thomas Gubler # sh /etc/init.d/rc.fw_defaults -echo "HIL Rascal 110 starting.." - set HIL yes 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 941f5664a..00b97d675 100644 --- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil +++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil @@ -2,7 +2,7 @@ # # HIL Malolo 1 (Flightgear) # -# Thomas Gubler +# Thomas Gubler # sh /etc/init.d/rc.fw_defaults diff --git a/ROMFS/px4fmu_common/init.d/11001_hexa_cox b/ROMFS/px4fmu_common/init.d/11001_hexa_cox index daa04a4de..e4d96fbd5 100644 --- a/ROMFS/px4fmu_common/init.d/11001_hexa_cox +++ b/ROMFS/px4fmu_common/init.d/11001_hexa_cox @@ -2,12 +2,12 @@ # # Generic 10" Hexa coaxial geometry # -# Lorenz Meier +# Lorenz Meier # sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_cox -# We only can run one channel group with one rate, so set all 8 channels +# Need to set all 8 channels set PWM_OUTPUTS 12345678 diff --git a/ROMFS/px4fmu_common/init.d/12001_octo_cox b/ROMFS/px4fmu_common/init.d/12001_octo_cox index 8703f5f2f..f820251ad 100644 --- a/ROMFS/px4fmu_common/init.d/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/12001_octo_cox @@ -2,7 +2,7 @@ # # Generic 10" Octo coaxial geometry # -# Lorenz Meier +# Lorenz Meier # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index 53c48d8aa..a7749cba6 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -2,7 +2,7 @@ # # Phantom FPV Flying Wing # -# Simon Wilks , Thomas Gubler +# Simon Wilks # sh /etc/init.d/rc.fw_defaults @@ -21,8 +21,6 @@ then param set FW_PR_P 0.03 param set FW_P_LIM_MAX 50 param set FW_P_LIM_MIN -50 - param set FW_P_RMAX_NEG 0 - param set FW_P_RMAX_POS 0 param set FW_P_ROLLFF 1 param set FW_RR_FF 0.5 param set FW_RR_I 0.02 diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index 7d0dc5bff..26c7c95e6 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -2,7 +2,7 @@ # # Skywalker X5 Flying Wing # -# Thomas Gubler , Julian Oes +# Thomas Gubler , Julian Oes # sh /etc/init.d/rc.fw_defaults @@ -19,10 +19,6 @@ then param set FW_PR_I 0 param set FW_PR_IMAX 0.2 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 1 param set FW_RR_FF 0.3 param set FW_RR_I 0 diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index f4dedef15..919eefb4a 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -2,7 +2,7 @@ # # Wing Wing (aka Z-84) Flying Wing # -# Simon Wilks +# Simon Wilks # sh /etc/init.d/rc.fw_defaults diff --git a/ROMFS/px4fmu_common/init.d/3034_fx79 b/ROMFS/px4fmu_common/init.d/3034_fx79 index f4bd18269..4a76ba6eb 100644 --- a/ROMFS/px4fmu_common/init.d/3034_fx79 +++ b/ROMFS/px4fmu_common/init.d/3034_fx79 @@ -2,7 +2,7 @@ # # FX-79 Buffalo Flying Wing # -# Simon Wilks +# Simon Wilks # sh /etc/init.d/rc.fw_defaults diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper index f3b0e8418..0f5f5502a 100644 --- a/ROMFS/px4fmu_common/init.d/3035_viper +++ b/ROMFS/px4fmu_common/init.d/3035_viper @@ -2,7 +2,7 @@ # # Viper # -# Simon Wilks +# Simon Wilks # sh /etc/init.d/rc.fw_defaults diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha index 9a2150403..9bfd9d9ed 100644 --- a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha @@ -1,8 +1,8 @@ #!nsh # -# TBS Caipirinha Flying Wing +# TBS Caipirinha # -# Thomas Gubler +# Thomas Gubler # sh /etc/init.d/rc.fw_defaults @@ -22,10 +22,6 @@ then param set FW_PR_I 0 param set FW_PR_IMAX 0.2 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.3 param set FW_RR_I 0 diff --git a/ROMFS/px4fmu_common/init.d/4001_quad_x b/ROMFS/px4fmu_common/init.d/4001_quad_x index 06c54a41d..8fe8961c5 100644 --- a/ROMFS/px4fmu_common/init.d/4001_quad_x +++ b/ROMFS/px4fmu_common/init.d/4001_quad_x @@ -2,7 +2,7 @@ # # Generic 10" Quad X geometry # -# Lorenz Meier +# Lorenz Meier # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/4008_ardrone b/ROMFS/px4fmu_common/init.d/4008_ardrone index e6007db0e..0488e3928 100644 --- a/ROMFS/px4fmu_common/init.d/4008_ardrone +++ b/ROMFS/px4fmu_common/init.d/4008_ardrone @@ -3,9 +3,6 @@ # ARDrone # -echo "[init] 4008_ardrone: PX4FMU on PX4IOAR carrier board" - -# Just use the default multicopter settings. sh /etc/init.d/rc.mc_defaults # diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index 282ab620d..f0cc05207 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -1,8 +1,8 @@ #!nsh # -# DJI Flame Wheel F330 Quadcopter +# DJI Flame Wheel F330 # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/4001_quad_x diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index 517b4aa86..1ca716a6b 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -1,8 +1,8 @@ #!nsh # -# DJI Flame Wheel F450 Quadcopter +# DJI Flame Wheel F450 # -# Lorenz Meier +# Lorenz Meier # sh /etc/init.d/4001_quad_x diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can index 8c5a4fbf2..5c4a6497a 100644 --- a/ROMFS/px4fmu_common/init.d/4012_quad_x_can +++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can @@ -2,7 +2,7 @@ # # F450-sized quadrotor with CAN # -# Lorenz Meier +# Pavel Kirienko # sh /etc/init.d/4001_quad_x diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 99ffd73a5..9fe310dde 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -3,7 +3,7 @@ # Hobbyking Micro Integrated PCB Quadcopter # with SimonK ESC firmware and Mystery A1510 motors # -# Thomas Gubler +# Thomas Gubler # echo "HK Micro PCB Quad" diff --git a/ROMFS/px4fmu_common/init.d/5001_quad_+ b/ROMFS/px4fmu_common/init.d/5001_quad_+ index 1fb25e5d8..5512aa738 100644 --- a/ROMFS/px4fmu_common/init.d/5001_quad_+ +++ b/ROMFS/px4fmu_common/init.d/5001_quad_+ @@ -2,7 +2,7 @@ # # Generic 10" Quad + geometry # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/6001_hexa_x b/ROMFS/px4fmu_common/init.d/6001_hexa_x index 34fc6523f..1043ad8ad 100644 --- a/ROMFS/px4fmu_common/init.d/6001_hexa_x +++ b/ROMFS/px4fmu_common/init.d/6001_hexa_x @@ -2,12 +2,12 @@ # # Generic 10" Hexa X geometry # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_x -# We only can run one channel group with one rate, so set all 8 channels +# Need to 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 235e376a6..84ab88883 100644 --- a/ROMFS/px4fmu_common/init.d/7001_hexa_+ +++ b/ROMFS/px4fmu_common/init.d/7001_hexa_+ @@ -2,12 +2,12 @@ # # Generic 10" Hexa + geometry # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults set MIXER FMU_hexa_+ -# We only can run one channel group with one rate, so set all 8 channels +# Need to 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 769217dc7..74e304cd9 100644 --- a/ROMFS/px4fmu_common/init.d/8001_octo_x +++ b/ROMFS/px4fmu_common/init.d/8001_octo_x @@ -2,7 +2,7 @@ # # Generic 10" Octo X geometry # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/9001_octo_+ b/ROMFS/px4fmu_common/init.d/9001_octo_+ index 28b074a54..f7c06c6c8 100644 --- a/ROMFS/px4fmu_common/init.d/9001_octo_+ +++ b/ROMFS/px4fmu_common/init.d/9001_octo_+ @@ -2,7 +2,7 @@ # # Generic 10" Octo + geometry # -# Anton Babushkin +# Anton Babushkin # sh /etc/init.d/rc.mc_defaults diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 78778d806..496a52c5f 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -1,5 +1,4 @@ # -# Check if auto-setup from one of the standard scripts is wanted # SYS_AUTOSTART = 0 means no autostart (default) # # AUTOSTART PARTITION: @@ -18,7 +17,7 @@ # 12000 .. 12999 Octo Cox # -# Simulation setups +# Simulation # if param compare SYS_AUTOSTART 901 @@ -53,7 +52,7 @@ then fi # -# Standard plane +# Plane # if param compare SYS_AUTOSTART 2100 100 diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 739df7ac0..fbac50cf7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -54,7 +54,6 @@ then fi fi -# Start airspeed sensors if meas_airspeed start then echo "[init] Using MEAS airspeed sensor" @@ -68,16 +67,12 @@ else fi fi -# Check for flow sensor if px4flow start then fi # -# Start the sensor collection task. -# IMPORTANT: this also loads param offsets -# ALWAYS start this task before the -# preflight_check. +# Start sensors -> preflight_check # if sensors start then diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index ea04ece34..f9c822635 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -137,9 +137,7 @@ then # if param compare SYS_AUTOCONFIG 1 then - # We can't be sure the defaults haven't changed, so - # if someone requests a re-configuration, we do it - # cleanly from scratch (except autostart / autoconfig) + # Wipe out params param reset_nostart set DO_AUTOCONFIG yes else @@ -202,12 +200,10 @@ then if px4io checkcrc $IO_FILE then - echo "[init] PX4IO CRC OK" echo "PX4IO CRC OK" >> $LOG_FILE set IO_PRESENT yes else - echo "[init] Trying to update" echo "PX4IO Trying to update" >> $LOG_FILE tone_alarm MLL32CP8MB @@ -217,18 +213,15 @@ then usleep 500000 if px4io checkcrc $IO_FILE then - echo "[init] PX4IO CRC OK, update successful" echo "PX4IO CRC OK after updating" >> $LOG_FILE tone_alarm MLL8CDE set IO_PRESENT yes else - echo "[init] ERROR: PX4IO update failed" echo "PX4IO update failed" >> $LOG_FILE tone_alarm $TUNE_OUT_ERROR fi else - echo "[init] ERROR: PX4IO update failed" echo "PX4IO update failed" >> $LOG_FILE tone_alarm $TUNE_OUT_ERROR fi @@ -281,16 +274,12 @@ then fi fi - # - # Start the datamanager (and do not abort boot if it fails) - # + # waypoint storage if dataman start then fi - # - # Start the Commander (needs to be this early for in-air-restarts) - # + # Needs to be this early for in-air-restarts commander start # @@ -424,9 +413,6 @@ then fi fi - # - # MAVLink - # if [ $MAVLINK_FLAGS == default ] then # Normal mode, use baudrate 57600 (default) and data rate 1000 bytes/s @@ -454,10 +440,6 @@ then # Sensors, Logging, GPS # sh /etc/init.d/rc.sensors - - # - # Start logging in all modes, including HIL - # sh /etc/init.d/rc.logging if [ $GPS == yes ] -- cgit v1.2.3 From e2c0ac3f700f003061e52fd61fd4770c982605c8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:40:29 +0100 Subject: airspeed driver: Be less chatty --- src/drivers/airspeed/airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/airspeed/airspeed.cpp b/src/drivers/airspeed/airspeed.cpp index 293690d27..3a1e1b7b5 100644 --- a/src/drivers/airspeed/airspeed.cpp +++ b/src/drivers/airspeed/airspeed.cpp @@ -147,7 +147,7 @@ Airspeed::init() _airspeed_pub = orb_advertise(ORB_ID(differential_pressure), &arp); if (_airspeed_pub < 0) - warnx("failed to create airspeed sensor object. uORB started?"); + warnx("uORB started?"); } ret = OK; -- cgit v1.2.3 From 6f71173f8c7a13565ef90a8fec44187ba392f038 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:40:42 +0100 Subject: ARDrone driver: be less chatty --- src/drivers/ardrone_interface/ardrone_interface.c | 36 +++++++++------------- .../ardrone_interface/ardrone_motor_control.c | 2 +- 2 files changed, 15 insertions(+), 23 deletions(-) diff --git a/src/drivers/ardrone_interface/ardrone_interface.c b/src/drivers/ardrone_interface/ardrone_interface.c index e5bb772b3..9d2c1441d 100644 --- a/src/drivers/ardrone_interface/ardrone_interface.c +++ b/src/drivers/ardrone_interface/ardrone_interface.c @@ -89,8 +89,8 @@ static void usage(const char *reason) { if (reason) - fprintf(stderr, "%s\n", reason); - fprintf(stderr, "usage: ardrone_interface {start|stop|status} [-d ]\n\n"); + warnx("%s\n", reason); + warnx("usage: {start|stop|status} [-d ]\n\n"); exit(1); } @@ -110,7 +110,7 @@ int ardrone_interface_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - printf("ardrone_interface already running\n"); + warnx("already running\n"); /* this is not an error */ exit(0); } @@ -132,9 +132,9 @@ int ardrone_interface_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - printf("\tardrone_interface is running\n"); + warnx("running"); } else { - printf("\tardrone_interface not started\n"); + warnx("not started"); } exit(0); } @@ -158,7 +158,7 @@ static int ardrone_open_uart(char *uart_name, struct termios *uart_config_origin /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - fprintf(stderr, "[ardrone_interface] ERROR getting baudrate / termios config for %s: %d\n", uart_name, termios_state); + warnx("ERR: TCGETATTR %s: %d", uart_name, termios_state); close(uart); return -1; } @@ -171,14 +171,14 @@ static int ardrone_open_uart(char *uart_name, struct termios *uart_config_origin /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); + warnx("ERR: cfsetispeed %s: %d", uart_name, termios_state); close(uart); return -1; } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); + warnx("ERR: tcsetattr: %s", uart_name); close(uart); return -1; } @@ -192,9 +192,6 @@ int ardrone_interface_thread_main(int argc, char *argv[]) char *device = "/dev/ttyS1"; - /* welcome user */ - printf("[ardrone_interface] Control started, taking over motors\n"); - /* File descriptors */ int gpios; @@ -237,7 +234,7 @@ int ardrone_interface_thread_main(int argc, char *argv[]) struct termios uart_config_original; if (motor_test_mode) { - printf("[ardrone_interface] Motor test mode enabled, setting 10 %% thrust.\n"); + warnx("setting 10 %% thrust.\n"); } /* Led animation */ @@ -255,9 +252,6 @@ int ardrone_interface_thread_main(int argc, char *argv[]) int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); int armed_sub = orb_subscribe(ORB_ID(actuator_armed)); - printf("[ardrone_interface] Motors initialized - ready.\n"); - fflush(stdout); - /* enable UART, writes potentially an empty buffer, but multiplexing is disabled */ ardrone_write = ardrone_open_uart(device, &uart_config_original); @@ -265,7 +259,7 @@ int ardrone_interface_thread_main(int argc, char *argv[]) gpios = ar_multiplexing_init(); if (ardrone_write < 0) { - fprintf(stderr, "[ardrone_interface] Failed opening AR.Drone UART, exiting.\n"); + warnx("No UART, exiting."); thread_running = false; exit(ERROR); } @@ -273,7 +267,7 @@ int ardrone_interface_thread_main(int argc, char *argv[]) /* initialize motors */ if (OK != ar_init_motors(ardrone_write, gpios)) { close(ardrone_write); - fprintf(stderr, "[ardrone_interface] Failed initializing AR.Drone motors, exiting.\n"); + warnx("motor init fail"); thread_running = false; exit(ERROR); } @@ -294,7 +288,7 @@ int ardrone_interface_thread_main(int argc, char *argv[]) gpios = ar_multiplexing_init(); if (ardrone_write < 0) { - fprintf(stderr, "[ardrone_interface] Failed opening AR.Drone UART, exiting.\n"); + warnx("write fail"); thread_running = false; exit(ERROR); } @@ -302,7 +296,7 @@ int ardrone_interface_thread_main(int argc, char *argv[]) /* initialize motors */ if (OK != ar_init_motors(ardrone_write, gpios)) { close(ardrone_write); - fprintf(stderr, "[ardrone_interface] Failed initializing AR.Drone motors, exiting.\n"); + warnx("motor init fail"); thread_running = false; exit(ERROR); } @@ -378,11 +372,9 @@ int ardrone_interface_thread_main(int argc, char *argv[]) int termios_state; if ((termios_state = tcsetattr(ardrone_write, TCSANOW, &uart_config_original)) < 0) { - fprintf(stderr, "[ardrone_interface] ERROR setting baudrate / termios config for (tcsetattr)\n"); + warnx("ERR: tcsetattr"); } - printf("[ardrone_interface] Restored original UART config, exiting..\n"); - /* close uarts */ close(ardrone_write); ar_multiplexing_deinit(gpios); diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c index fc017dd58..4fa24275f 100644 --- a/src/drivers/ardrone_interface/ardrone_motor_control.c +++ b/src/drivers/ardrone_interface/ardrone_motor_control.c @@ -301,7 +301,7 @@ int ar_init_motors(int ardrone_uart, int gpios) ardrone_write_motor_commands(ardrone_uart, 0, 0, 0, 0); if (errcounter != 0) { - fprintf(stderr, "[ardrone_interface] init sequence incomplete, failed %d times", -errcounter); + warnx("Failed %d times", -errcounter); fflush(stdout); } return errcounter; -- cgit v1.2.3 From 8d5225b9679c2820a57ea30ed6d4c46f5d6c9baa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:41:18 +0100 Subject: FrSky: Be less chatty --- src/drivers/frsky_telemetry/frsky_telemetry.c | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/drivers/frsky_telemetry/frsky_telemetry.c b/src/drivers/frsky_telemetry/frsky_telemetry.c index 6e0839043..bccdf1190 100644 --- a/src/drivers/frsky_telemetry/frsky_telemetry.c +++ b/src/drivers/frsky_telemetry/frsky_telemetry.c @@ -84,7 +84,7 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or /* Back up the original UART configuration to restore it after exit */ int termios_state; if ((termios_state = tcgetattr(uart, uart_config_original)) < 0) { - warnx("ERROR get termios config %s: %d\n", uart_name, termios_state); + warnx("ERR: tcgetattr%s: %d\n", uart_name, termios_state); close(uart); return -1; } @@ -100,13 +100,13 @@ static int frsky_open_uart(const char *uart_name, struct termios *uart_config_or static const speed_t speed = B9600; if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - warnx("ERROR setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); + warnx("ERR: %s: %d (cfsetispeed, cfsetospeed)\n", uart_name, termios_state); close(uart); return -1; } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { - warnx("ERROR setting baudrate / termios config for %s (tcsetattr)\n", uart_name); + warnx("ERR: %s (tcsetattr)\n", uart_name); close(uart); return -1; } @@ -151,9 +151,6 @@ static int frsky_telemetry_thread_main(int argc, char *argv[]) } } - /* Print welcome text */ - warnx("FrSky telemetry interface starting..."); - /* Open UART */ struct termios uart_config_original; const int uart = frsky_open_uart(device_name, &uart_config_original); -- cgit v1.2.3 From ef27225534df6cca0b5a98b85c6b7cf3364493c0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:41:30 +0100 Subject: HIL: Be less chatty --- src/drivers/hil/hil.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index f0dc0c651..9b5c8133b 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -442,8 +442,6 @@ HIL::task_main() /* make sure servos are off */ // up_pwm_servo_deinit(); - log("stopping"); - /* note - someone else is responsible for restoring the GPIO config */ /* tell the dtor that we are exiting */ -- cgit v1.2.3 From 5af710221a2948ab14f95225b4cb6c7fe5c66560 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:54:34 +0100 Subject: HoTT: Less chatty --- src/drivers/hott/comms.cpp | 8 ++++---- src/drivers/hott/hott_sensors/hott_sensors.cpp | 6 +++--- src/drivers/hott/hott_telemetry/hott_telemetry.cpp | 6 +++--- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/drivers/hott/comms.cpp b/src/drivers/hott/comms.cpp index cb8bbba37..60a49b559 100644 --- a/src/drivers/hott/comms.cpp +++ b/src/drivers/hott/comms.cpp @@ -55,7 +55,7 @@ open_uart(const char *device) const int uart = open(device, O_RDWR | O_NOCTTY); if (uart < 0) { - err(1, "Error opening port: %s", device); + err(1, "ERR: opening %s", device); } /* Back up the original uart configuration to restore it after exit */ @@ -63,7 +63,7 @@ open_uart(const char *device) struct termios uart_config_original; if ((termios_state = tcgetattr(uart, &uart_config_original)) < 0) { close(uart); - err(1, "Error getting baudrate / termios config for %s: %d", device, termios_state); + err(1, "ERR: %s: %d", device, termios_state); } /* Fill the struct for the new configuration */ @@ -76,13 +76,13 @@ open_uart(const char *device) /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { close(uart); - err(1, "Error setting baudrate / termios config for %s: %d (cfsetispeed, cfsetospeed)", + err(1, "ERR: %s: %d (cfsetispeed, cfsetospeed)", device, termios_state); } if ((termios_state = tcsetattr(uart, TCSANOW, &uart_config)) < 0) { close(uart); - err(1, "Error setting baudrate / termios config for %s (tcsetattr)", device); + err(1, "ERR: %s (tcsetattr)", device); } /* Activate single wire mode */ diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp index a3d3a3933..8ab9d8d55 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.cpp +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -204,7 +204,7 @@ hott_sensors_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - warnx("deamon already running"); + warnx("already running"); exit(0); } @@ -225,10 +225,10 @@ hott_sensors_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - warnx("daemon is running"); + warnx("is running"); } else { - warnx("daemon not started"); + warnx("not started"); } exit(0); diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp index d293f9954..edbb14172 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp @@ -230,7 +230,7 @@ hott_telemetry_main(int argc, char *argv[]) if (!strcmp(argv[1], "start")) { if (thread_running) { - warnx("deamon already running"); + warnx("already running"); exit(0); } @@ -251,10 +251,10 @@ hott_telemetry_main(int argc, char *argv[]) if (!strcmp(argv[1], "status")) { if (thread_running) { - warnx("daemon is running"); + warnx("is running"); } else { - warnx("daemon not started"); + warnx("not started"); } exit(0); -- cgit v1.2.3 From 1fc7b588945b3bb1df70de1f779201c60a803b71 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:54:47 +0100 Subject: Bottle drop: Less chatty --- src/modules/bottle_drop/bottle_drop.cpp | 19 +++++++++---------- 1 file changed, 9 insertions(+), 10 deletions(-) diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp index 31c9157e1..6d24e5d2d 100644 --- a/src/modules/bottle_drop/bottle_drop.cpp +++ b/src/modules/bottle_drop/bottle_drop.cpp @@ -283,7 +283,6 @@ BottleDrop::drop() // force the door open if we have to if (_doors_opened == 0) { open_bay(); - warnx("bay not ready, forced open"); } while (hrt_elapsed_time(&_doors_opened) < 500 * 1000 && hrt_elapsed_time(&starttime) < 2000000) { @@ -723,16 +722,16 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) if (cmd->param1 > 0.5f && cmd->param2 > 0.5f) { open_bay(); drop(); - mavlink_log_info(_mavlink_fd, "#audio: drop bottle"); + mavlink_log_critical(_mavlink_fd, "drop bottle"); } else if (cmd->param1 > 0.5f) { open_bay(); - mavlink_log_info(_mavlink_fd, "#audio: opening bay"); + mavlink_log_critical(_mavlink_fd, "opening bay"); } else { lock_release(); close_bay(); - mavlink_log_info(_mavlink_fd, "#audio: closing bay"); + mavlink_log_critical(_mavlink_fd, "closing bay"); } answer_command(cmd, VEHICLE_CMD_RESULT_ACCEPTED); @@ -743,12 +742,12 @@ BottleDrop::handle_command(struct vehicle_command_s *cmd) switch ((int)(cmd->param1 + 0.5f)) { case 0: _drop_approval = false; - mavlink_log_info(_mavlink_fd, "#audio: got drop position, no approval"); + mavlink_log_critical(_mavlink_fd, "got drop position, no approval"); break; case 1: _drop_approval = true; - mavlink_log_info(_mavlink_fd, "#audio: got drop position and approval"); + mavlink_log_critical(_mavlink_fd, "got drop position and approval"); break; default: @@ -818,19 +817,19 @@ BottleDrop::answer_command(struct vehicle_command_s *cmd, enum VEHICLE_CMD_RESUL break; case VEHICLE_CMD_RESULT_DENIED: - mavlink_log_critical(_mavlink_fd, "#audio: command denied: %u", cmd->command); + mavlink_log_critical(_mavlink_fd, "command denied: %u", cmd->command); break; case VEHICLE_CMD_RESULT_FAILED: - mavlink_log_critical(_mavlink_fd, "#audio: command failed: %u", cmd->command); + mavlink_log_critical(_mavlink_fd, "command failed: %u", cmd->command); break; case VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED: - mavlink_log_critical(_mavlink_fd, "#audio: command temporarily rejected: %u", cmd->command); + mavlink_log_critical(_mavlink_fd, "command temporarily rejected: %u", cmd->command); break; case VEHICLE_CMD_RESULT_UNSUPPORTED: - mavlink_log_critical(_mavlink_fd, "#audio: command unsupported: %u", cmd->command); + mavlink_log_critical(_mavlink_fd, "command unsupported: %u", cmd->command); break; default: -- cgit v1.2.3 From beee7a89ed6e7a7c98ee712ab571c58eb6f3a692 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:55:04 +0100 Subject: Airspeed: less chatty --- src/drivers/meas_airspeed/meas_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 1d9a463ad..ba46de379 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -519,7 +519,7 @@ test() ret = poll(&fds, 1, 2000); if (ret != 1) { - errx(1, "timed out waiting for sensor data"); + errx(1, "timed out"); } /* now go get it */ -- cgit v1.2.3 From d602c9a0c5eff39e0f533411b45f631cae63e486 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 16:55:18 +0100 Subject: Controllib: Optimize for size --- src/modules/controllib/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/controllib/module.mk b/src/modules/controllib/module.mk index f0139a4b7..2860d1efc 100644 --- a/src/modules/controllib/module.mk +++ b/src/modules/controllib/module.mk @@ -39,3 +39,5 @@ SRCS = test_params.c \ block/BlockParam.cpp \ uorb/blocks.cpp \ blocks.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 9c7503ba7a3f5d8f98ab3017d221192489d0b3c9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 18:38:33 +0100 Subject: uORB: Save space, does not do complex operations --- src/modules/uORB/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/uORB/module.mk b/src/modules/uORB/module.mk index 0c29101fe..9385ce253 100644 --- a/src/modules/uORB/module.mk +++ b/src/modules/uORB/module.mk @@ -44,3 +44,5 @@ SRCS = uORB.cpp \ objects_common.cpp \ Publication.cpp \ Subscription.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 488739cc467cea08374e97f96f70317376ec58ec Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 19:13:46 +0100 Subject: Fix up ver command handling to print MCU version on all command as well --- src/systemcmds/ver/ver.c | 58 ++++++++++++++++++++++++++++-------------------- 1 file changed, 34 insertions(+), 24 deletions(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 62a7a5b92..eebeb9289 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -46,7 +46,7 @@ #include #include -// string constants for version commands +/* 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"; @@ -68,49 +68,56 @@ __EXPORT int ver_main(int argc, char *argv[]); int ver_main(int argc, char *argv[]) { - int ret = 1; //defaults to an error + /* defaults to an error */ + int ret = 1; - // first check if there are at least 2 params + /* 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 (!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 + /* 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); + return ret; } } 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; + /* check if we want to show all */ + bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)) - } else if (!strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { - printf("%s %s\n", __DATE__, __TIME__); + if (show_all || !strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { + printf("HW arch: %s\n", HW_ARCH); ret = 0; - } else if (!strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { - printf("%s\n", __VERSION__); + } + + if (show_all || !strncmp(argv[1], sz_ver_git_str, sizeof(sz_ver_git_str))) { + printf("FW git-hash: %s\n", FW_GIT); ret = 0; - } else if (!strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str))) { - printf("HW arch: %s\n", HW_ARCH); + } + + if (show_all || !strncmp(argv[1], sz_ver_bdate_str, sizeof(sz_ver_bdate_str))) { 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 if (!strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { + if (show_all || !strncmp(argv[1], sz_ver_gcc_str, sizeof(sz_ver_gcc_str))) { + printf("Toolchain: %s\n", __VERSION__); + ret = 0; + + } + + if (show_all || !strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) { char rev; char* revstr; @@ -118,21 +125,24 @@ int ver_main(int argc, char *argv[]) int chip_version = mcu_version(&rev, &revstr); if (chip_version < 0) { - printf("UNKNOWN MCU"); + printf("UNKNOWN MCU\n"); ret = 1; } else { printf("MCU: %s, rev. %c\n", revstr, rev); if (chip_version < MCU_REV_STM32F4_REV_3) { - printf("\n\nWARNING WARNING WARNING!\n" + printf("\nWARNING WARNING WARNING!\n" "Revision %c has a silicon errata\n" "This device can only utilize a maximum of 1MB flash safely!\n" - "http://px4.io/help/errata\n", rev); + "http://px4.io/help/errata\n\n", rev); } } - } else { + ret = 0; + } + + if (ret = 1) { errx(1, "unknown command.\n"); } -- cgit v1.2.3 From ed0f28ed4191c296aa3592088dc7875a8246cabb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 19:43:11 +0100 Subject: Fix ver command --- src/systemcmds/ver/ver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index eebeb9289..55cec149f 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -91,7 +91,7 @@ int ver_main(int argc, char *argv[]) } /* check if we want to show all */ - bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)) + bool show_all = !strncmp(argv[1], sz_ver_all_str, sizeof(sz_ver_all_str)); if (show_all || !strncmp(argv[1], sz_ver_hw_str, sizeof(sz_ver_hw_str))) { printf("HW arch: %s\n", HW_ARCH); -- cgit v1.2.3 From e2551d491754b752b8b835a302acaf3f4cf1f9d6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 20:05:54 +0100 Subject: Fixed typo in ver command --- src/systemcmds/ver/ver.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index 55cec149f..c794f5819 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -126,7 +126,6 @@ int ver_main(int argc, char *argv[]) if (chip_version < 0) { printf("UNKNOWN MCU\n"); - ret = 1; } else { printf("MCU: %s, rev. %c\n", revstr, rev); @@ -142,7 +141,7 @@ int ver_main(int argc, char *argv[]) ret = 0; } - if (ret = 1) { + if (ret == 1) { errx(1, "unknown command.\n"); } -- cgit v1.2.3 From 18dc5e342905f6171b54adba6de8a27d65d62ab2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 15 Nov 2014 20:07:32 +0100 Subject: Fix compile warning in MAVLink app --- src/modules/mavlink/mavlink_messages.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index b4911427f..bed915bbe 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -382,11 +382,11 @@ protected: clock_gettime(CLOCK_REALTIME, &ts); /* use GPS time for log file naming, e.g. /fs/microsd/2014-01-19/19_37_52.bin */ time_t gps_time_sec = ts.tv_sec + (ts.tv_nsec / 1e9); - struct tm t; - gmtime_r(&gps_time_sec, &t); + struct tm tt; + gmtime_r(&gps_time_sec, &tt); // XXX we do not want to interfere here with the SD log app - strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &t); + strftime(log_file_name, sizeof(log_file_name), "msgs_%Y_%m_%d_%H_%M_%S.txt", &tt); snprintf(log_file_path, sizeof(log_file_path), "/fs/microsd/%s", log_file_name); fp = fopen(log_file_path, "ab"); } -- cgit v1.2.3 From c0f32d44a2acd0f840b4246f90816a95dc6a7527 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 00:15:40 +0100 Subject: First stab at animation --- src/modules/px4iofirmware/px4io.c | 40 ++++++++++++++++++++++++++++++++++++++- 1 file changed, 39 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index 30f32b38e..51281f660 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -125,7 +125,45 @@ heartbeat_blink(void) static bool heartbeat = false; LED_BLUE(heartbeat = !heartbeat); #ifdef GPIO_LED4 - LED_RING(heartbeat); + + const unsigned max_brightness = 1000; + + static unsigned counter = 0; + static unsigned brightness = max_brightness; + static unsigned brightness_counter = 0; + static unsigned on_counter = 0; + + if (brightness_counter < max_brightness) { + + bool on = ((on_counter * 100) / brightness_counter) <= ((brightness * 100) / max_brightness); + + LED_RING(on); + brightness_counter++; + + if (on) { + on_counter++; + } + + } else { + + if (counter >= 62) { + counter = 0; + } + + int n; + + if (counter < 32) { + n = counter; + + } else { + n = 62 - counter; + } + + brightness = n * n;// designed to be ~1000 / (31.0f * 31.0f); + brightness_counter = 0; + on_counter = 0; + } + #endif } -- cgit v1.2.3 From 63707ef058f01e324d8d74cf6bc48635e09ab507 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 00:57:23 +0100 Subject: Let it breathe --- src/modules/px4iofirmware/px4io.c | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index 51281f660..8abfb0d2e 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -85,6 +85,9 @@ static volatile uint8_t msg_next_out, msg_next_in; #define NUM_MSG 2 static char msg[NUM_MSG][40]; +static void heartbeat_blink(void); +static void ring_blink(void); + /* * add a debug message to be printed on the console */ @@ -124,9 +127,16 @@ heartbeat_blink(void) { static bool heartbeat = false; LED_BLUE(heartbeat = !heartbeat); +} + +static void +ring_blink(void) +{ #ifdef GPIO_LED4 - const unsigned max_brightness = 1000; + // XXX this led code does have + // intentionally a few magic numbers. + const unsigned max_brightness = 118; static unsigned counter = 0; static unsigned brightness = max_brightness; @@ -135,7 +145,7 @@ heartbeat_blink(void) if (brightness_counter < max_brightness) { - bool on = ((on_counter * 100) / brightness_counter) <= ((brightness * 100) / max_brightness); + bool on = ((on_counter * 100) / brightness_counter+1) <= ((brightness * 100) / max_brightness+1); LED_RING(on); brightness_counter++; @@ -159,9 +169,10 @@ heartbeat_blink(void) n = 62 - counter; } - brightness = n * n;// designed to be ~1000 / (31.0f * 31.0f); + brightness = (n * n) / 9; brightness_counter = 0; on_counter = 0; + counter++; } #endif @@ -338,6 +349,8 @@ user_start(int argc, char *argv[]) heartbeat_blink(); } + ring_blink(); + check_reboot(); /* check for debug activity (default: none) */ -- cgit v1.2.3 From 8583cf4dcc0e88842cdf717de26a4f0daa63729a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 00:59:18 +0100 Subject: Let it breathe stronger --- src/modules/px4iofirmware/px4io.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index 8abfb0d2e..349aaac57 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -169,7 +169,7 @@ ring_blink(void) n = 62 - counter; } - brightness = (n * n) / 9; + brightness = (n * n) / 8; brightness_counter = 0; on_counter = 0; counter++; -- cgit v1.2.3 From 8caada2188b9c9a8fcab70fbad92ab14506c2427 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 01:21:47 +0100 Subject: Breathe animation, led solid on arming --- src/modules/px4iofirmware/px4io.c | 14 ++++++++++++-- src/modules/px4iofirmware/px4io.h | 2 +- 2 files changed, 13 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c index 349aaac57..14ee9cb40 100644 --- a/src/modules/px4iofirmware/px4io.c +++ b/src/modules/px4iofirmware/px4io.c @@ -134,6 +134,12 @@ ring_blink(void) { #ifdef GPIO_LED4 + if (/* IO armed */ (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) + /* and FMU is armed */ && (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) { + LED_RING(1); + return; + } + // XXX this led code does have // intentionally a few magic numbers. const unsigned max_brightness = 118; @@ -147,7 +153,11 @@ ring_blink(void) bool on = ((on_counter * 100) / brightness_counter+1) <= ((brightness * 100) / max_brightness+1); - LED_RING(on); + // XXX once led is PWM driven, + // remove the ! in the line below + // to return to the proper breathe + // animation / pattern (currently inverted) + LED_RING(!on); brightness_counter++; if (on) { @@ -349,7 +359,7 @@ user_start(int argc, char *argv[]) heartbeat_blink(); } - ring_blink(); + ring_blink(); check_reboot(); diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index 8186e4c78..93a33490f 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -140,7 +140,7 @@ extern pwm_limit_t pwm_limit; #define LED_BLUE(_s) stm32_gpiowrite(GPIO_LED1, !(_s)) #define LED_AMBER(_s) stm32_gpiowrite(GPIO_LED2, !(_s)) #define LED_SAFETY(_s) stm32_gpiowrite(GPIO_LED3, !(_s)) -#define LED_RING(_s) stm32_gpiowrite(GPIO_LED4, !(_s)) +#define LED_RING(_s) stm32_gpiowrite(GPIO_LED4, (_s)) #ifdef CONFIG_ARCH_BOARD_PX4IO_V1 -- cgit v1.2.3 From 4e8387465e01cf16e0fbbe94b5e9a3c168540b77 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 16 Nov 2014 13:38:41 +1000 Subject: navigator: only update sensor_combined topic with 50Hz --- src/modules/navigator/navigator_main.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index e933919fb..ed9e999a9 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -289,8 +289,9 @@ Navigator::task_main() navigation_capabilities_update(); params_update(); - /* rate limit position updates to 50 Hz */ + /* rate limit position and sensor updates to 50 Hz */ orb_set_interval(_global_pos_sub, 20); + orb_set_interval(_sensor_combined_sub, 20); hrt_abstime mavlink_open_time = 0; const hrt_abstime mavlink_open_interval = 500000; -- cgit v1.2.3 From 4d69314a9925be8ded1b9cb723bd01c21f01a816 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 10:55:18 +0100 Subject: Adjust navigator priority --- 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 ed9e999a9..3ca6ac2c0 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -498,7 +498,7 @@ Navigator::start() /* start the task */ _navigator_task = task_spawn_cmd("navigator", SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 5, + SCHED_PRIORITY_DEFAULT + 20, 2000, (main_t)&Navigator::task_main_trampoline, nullptr); -- cgit v1.2.3 From 88bae21ce53fc6acadaae4c8271f3d0fce18a721 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 5 Nov 2014 21:20:32 +1100 Subject: px4io: added RC_CONFIG, SET_OVERRIDE_OK and CLEAR_OVERRIDE_OK ioctls this allows for full setup of RC override without needing param_get() to PX4 specific parameters --- src/drivers/drv_pwm_output.h | 26 ++++++++++++++++++++++++++ src/drivers/px4io/px4io.cpp | 36 ++++++++++++++++++++++++++++++++++++ 2 files changed, 62 insertions(+) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 6873f24b6..b41f088eb 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -117,6 +117,23 @@ struct pwm_output_values { unsigned channel_count; }; + +/** + * RC config values for a channel + * + * This allows for PX4IO_PAGE_RC_CONFIG values to be set without a + * param_get() dependency + */ +struct pwm_output_rc_config { + uint8_t channel; + uint16_t rc_min; + uint16_t rc_trim; + uint16_t rc_max; + uint16_t rc_dz; + uint16_t rc_assignment; + bool rc_reverse; +}; + /* * ORB tag for PWM outputs. */ @@ -216,6 +233,15 @@ ORB_DECLARE(output_pwm); /** force safety switch on (to enable use of safety switch) */ #define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26) +/** set RC config for a channel. This takes a pointer to pwm_output_rc_config */ +#define PWM_SERVO_SET_RC_CONFIG _IOC(_PWM_SERVO_BASE, 27) + +/** set the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */ +#define PWM_SERVO_SET_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 28) + +/** clear the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */ +#define PWM_SERVO_CLEAR_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 29) + /* * * diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 06faf49a4..dc33f7657 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2572,6 +2572,42 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg) break; + case PWM_SERVO_SET_RC_CONFIG: { + /* enable setting of RC configuration without relying + on param_get() + */ + struct pwm_output_rc_config* config = (struct pwm_output_rc_config*)arg; + if (config->channel >= _max_actuators) { + /* fail with error */ + return E2BIG; + } + + /* copy values to registers in IO */ + uint16_t regs[PX4IO_P_RC_CONFIG_STRIDE]; + uint16_t offset = config->channel * PX4IO_P_RC_CONFIG_STRIDE; + regs[PX4IO_P_RC_CONFIG_MIN] = config->rc_min; + regs[PX4IO_P_RC_CONFIG_CENTER] = config->rc_trim; + regs[PX4IO_P_RC_CONFIG_MAX] = config->rc_max; + regs[PX4IO_P_RC_CONFIG_DEADZONE] = config->rc_dz; + regs[PX4IO_P_RC_CONFIG_ASSIGNMENT] = config->rc_assignment; + regs[PX4IO_P_RC_CONFIG_OPTIONS] = PX4IO_P_RC_CONFIG_OPTIONS_ENABLED; + if (config->rc_reverse) { + regs[PX4IO_P_RC_CONFIG_OPTIONS] |= PX4IO_P_RC_CONFIG_OPTIONS_REVERSE; + } + ret = io_reg_set(PX4IO_PAGE_RC_CONFIG, offset, regs, PX4IO_P_RC_CONFIG_STRIDE); + break; + } + + case PWM_SERVO_SET_OVERRIDE_OK: + /* set the 'OVERRIDE OK' bit */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK); + break; + + case PWM_SERVO_CLEAR_OVERRIDE_OK: + /* clear the 'OVERRIDE OK' bit */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_MANUAL_OVERRIDE_OK, 0); + break; + default: /* see if the parent class can make any use of it */ ret = CDev::ioctl(filep, cmd, arg); -- cgit v1.2.3 From 6406e235d6f5cb37a914442036111f616b4b3839 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 6 Nov 2014 10:32:21 +1100 Subject: px4io: publish pwm values when STATUS_FLAGS_FMU_OK is not set this allows testing of FMU failure behaviour in px4io by monitoring the reported PWM output when the vehicle code stops sending updates. Otherwise testing needs to be done with "px4io status" which is very tedious. With this change a GCS can monitor the PWM outputs from the failsafe mixer using normal mavlink messages --- src/drivers/px4io/px4io.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index dc33f7657..6a313b322 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1657,10 +1657,6 @@ PX4IO::io_publish_raw_rc() int PX4IO::io_publish_pwm_outputs() { - /* if no FMU comms(!) just don't publish */ - if (!(_status & PX4IO_P_STATUS_FLAGS_FMU_OK)) - return OK; - /* data we are going to fetch */ actuator_outputs_s outputs; outputs.timestamp = hrt_absolute_time(); -- cgit v1.2.3 From ba811254536b6a080d4b3379106bf0e648a51eb0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 5 Nov 2014 21:20:03 +1100 Subject: px4io: added OVERRIDE_IMMEDIATE arming flag this allows the flight code to choose whether FMU failure gives immediate manual pilot control, or waits for the mode switch to go past the override threshold --- src/drivers/drv_pwm_output.h | 3 +++ src/drivers/px4io/px4io.cpp | 18 ++++++++++++++++-- src/modules/px4iofirmware/controls.c | 9 +++++++++ src/modules/px4iofirmware/protocol.h | 1 + src/modules/px4iofirmware/registers.c | 3 ++- 5 files changed, 31 insertions(+), 3 deletions(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index b41f088eb..edb72f04e 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -242,6 +242,9 @@ ORB_DECLARE(output_pwm); /** clear the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */ #define PWM_SERVO_CLEAR_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 29) +/** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */ +#define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _IOC(_PWM_SERVO_BASE, 30) + /* * * diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 6a313b322..519ba663a 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2057,7 +2057,7 @@ PX4IO::print_status(bool extended_status) ((features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) ? " RSSI_ADC" : "") ); uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING); - printf("arming 0x%04x%s%s%s%s%s%s%s%s\n", + printf("arming 0x%04x%s%s%s%s%s%s%s%s%s%s\n", arming, ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"), ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"), @@ -2067,7 +2067,8 @@ PX4IO::print_status(bool extended_status) ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""), ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""), ((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : ""), - ((arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) ? " TERM_FAILSAFE" : "") + ((arming & PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) ? " TERM_FAILSAFE" : ""), + ((arming & PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) ? " OVERRIDE_IMMEDIATE" : "") ); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 printf("rates 0x%04x default %u alt %u relays 0x%04x\n", @@ -2307,6 +2308,19 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg) } break; + case PWM_SERVO_SET_OVERRIDE_IMMEDIATE: + /* control whether override on FMU failure is + immediate or waits for override threshold on mode + switch */ + if (arg == 0) { + /* clear override immediate flag */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE, 0); + } else { + /* set override immediate flag */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE); + } + break; + case DSM_BIND_START: /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */ diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index ad60ee03e..e3cb8d820 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -417,6 +417,15 @@ controls_tick() { if ((r_status_flags & PX4IO_P_STATUS_FLAGS_RC_OK) && (REG_TO_SIGNED(rc_value_override) < RC_CHANNEL_LOW_THRESH)) override = true; + /* + if the FMU is dead then enable override if we have a + mixer and OVERRIDE_IMMEDIATE is set + */ + if (!(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK) && + (r_setup_arming & PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) && + (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK)) + override = true; + if (override) { r_status_flags |= PX4IO_P_STATUS_FLAGS_OVERRIDE; diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index 9b2e047cb..c7e9ae3eb 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -183,6 +183,7 @@ #define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */ #define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */ #define PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE (1 << 9) /* If set, the system will never return from a failsafe, but remain in failsafe once triggered. */ +#define PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE (1 << 10) /* If set then on FMU failure override is immediate. Othewise it waits for the mode switch to go past the override thrshold */ #define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */ #define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */ diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 49c2a9f56..fbfdd35db 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -191,7 +191,8 @@ volatile uint16_t r_page_setup[] = PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \ PX4IO_P_SETUP_ARMING_LOCKDOWN | \ PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE | \ - PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE) + PX4IO_P_SETUP_ARMING_TERMINATION_FAILSAFE | \ + PX4IO_P_SETUP_ARMING_OVERRIDE_IMMEDIATE) #define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1) #define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1) -- cgit v1.2.3 From f533c362515e31b536c34d83342c396e54a7d652 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 5 Nov 2014 21:20:32 +1100 Subject: px4io: added RC_CONFIG, SET_OVERRIDE_OK and CLEAR_OVERRIDE_OK ioctls this allows for full setup of RC override without needing param_get() to PX4 specific parameters Conflicts: src/drivers/drv_pwm_output.h --- src/drivers/drv_pwm_output.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index edb72f04e..b10c3e18a 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -231,16 +231,16 @@ ORB_DECLARE(output_pwm); #define PWM_SERVO_SET_TERMINATION_FAILSAFE _IOC(_PWM_SERVO_BASE, 25) /** force safety switch on (to enable use of safety switch) */ -#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26) +#define PWM_SERVO_SET_FORCE_SAFETY_ON _IOC(_PWM_SERVO_BASE, 26) /** set RC config for a channel. This takes a pointer to pwm_output_rc_config */ -#define PWM_SERVO_SET_RC_CONFIG _IOC(_PWM_SERVO_BASE, 27) +#define PWM_SERVO_SET_RC_CONFIG _IOC(_PWM_SERVO_BASE, 27) /** set the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */ -#define PWM_SERVO_SET_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 28) +#define PWM_SERVO_SET_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 28) /** clear the 'OVERRIDE OK' bit, which allows for RC control on FMU loss */ -#define PWM_SERVO_CLEAR_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 29) +#define PWM_SERVO_CLEAR_OVERRIDE_OK _IOC(_PWM_SERVO_BASE, 29) /** setup OVERRIDE_IMMEDIATE behaviour on FMU fail */ #define PWM_SERVO_SET_OVERRIDE_IMMEDIATE _IOC(_PWM_SERVO_BASE, 30) -- cgit v1.2.3 From 852fa611730be2433156b010c6162606ec857ef3 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 16 Nov 2014 14:12:58 -0800 Subject: Correct setting of DSM and ST24 flags --- src/modules/px4iofirmware/controls.c | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 3fd73fc60..75d80ba5d 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -71,7 +71,6 @@ bool dsm_port_input(uint16_t *rssi, bool *dsm_updated, bool *st24_updated) uint8_t *bytes; *dsm_updated = dsm_input(r_raw_rc_values, &temp_count, &n_bytes, &bytes); if (*dsm_updated) { - r_raw_rc_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM; r_raw_rc_count = temp_count & 0x7fff; if (temp_count & 0x8000) r_raw_rc_flags |= PX4IO_P_RAW_RC_FLAGS_RC_DSM11; @@ -172,6 +171,12 @@ controls_tick() { perf_begin(c_gather_dsm); bool dsm_updated, st24_updated; (void)dsm_port_input(&rssi, &dsm_updated, &st24_updated); + if (dsm_updated) { + r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_DSM; + } + if (st24_updated) { + r_status_flags |= PX4IO_P_STATUS_FLAGS_RC_ST24; + } perf_end(c_gather_dsm); perf_begin(c_gather_sbus); -- cgit v1.2.3 From 52d5a7c00aa74fe0d4241f7e6636dfd6e48d0acf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 16 Nov 2014 23:24:52 +0100 Subject: Fix PWM command --- src/systemcmds/pwm/pwm.c | 68 ++++++++++++++++++++++++------------------------ 1 file changed, 34 insertions(+), 34 deletions(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 478c2a772..eeba89fa8 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -74,34 +74,34 @@ usage(const char *reason) "usage:\n" "pwm arm|disarm|rate|failsafe|disarmed|min|max|test|info ...\n" "\n" - " arm Arm output\n" - " disarm Disarm output\n" + "arm\t\t\t\tArm output\n" + "disarm\t\t\t\tDisarm output\n" "\n" - " rate ... Configure PWM rates\n" - " [-g ] Channel group that should update at the alternate rate\n" - " [-m ] Directly supply channel mask\n" - " [-a] Configure all outputs\n" - " -r PWM rate (50 to 400 Hz)\n" + "rate ...\t\t\tConfigure PWM rates\n" + "\t[-g ]\t(e.g. 0,1,2)\n" + "\t[-m ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-r \t\tPWM rate (50 to 400 Hz)\n" "\n" - " failsafe ... Configure failsafe PWM values\n" - " disarmed ... Configure disarmed PWM values\n" - " min ... Configure minimum PWM values\n" - " max ... Configure maximum PWM values\n" - " [-c ] Supply channels (e.g. 1234)\n" - " [-m ] Directly supply channel mask (e.g. 0xF)\n" - " [-a] Configure all outputs\n" - " -p PWM value\n" + "failsafe ...\t\t\tFailsafe PWM\n" + "disarmed ...\t\t\tDisarmed PWM\n" + "min ...\t\t\t\tMinimum PWM\n" + "max ...\t\t\t\tMaximum PWM\n" + "\t[-c ]\t\t(e.g. 1234)\n" + "\t[-m ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-p \t\tPWM value\n" "\n" - " test ... Directly set PWM values\n" - " [-c ] Supply channels (e.g. 1234)\n" - " [-m ] Directly supply channel mask (e.g. 0xF)\n" - " [-a] Configure all outputs\n" - " -p PWM value\n" + "test ...\t\t\tDirectly set PWM\n" + "\t[-c ]\t\t(e.g. 1234)\n" + "\t[-m ]\t(e.g. 0xF)\n" + "\t[-a]\t\t\tConfigure all outputs\n" + "\t-p \t\tPWM value\n" "\n" - " info Print information about the PWM device\n" + "info\t\t\t\tPrint information\n" "\n" - " -v Print verbose information\n" - " -d PWM output device (defaults to " PWM_OUTPUT_DEVICE_PATH ")\n" + "\t-v\t\t\tVerbose\n" + "\t-d \t\t(default " PWM_OUTPUT_DEVICE_PATH ")\n" ); } @@ -123,7 +123,7 @@ pwm_main(int argc, char *argv[]) unsigned single_ch = 0; unsigned pwm_value = 0; - if (argc < 1) + if (argc < 2) usage(NULL); while ((ch = getopt(argc-1, &argv[1], "d:vc:g:m:ap:r:")) != EOF) { @@ -165,7 +165,7 @@ pwm_main(int argc, char *argv[]) /* Read in mask directly */ set_mask = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad set_mask value"); + usage("BAD set_mask VAL"); break; case 'a': @@ -176,12 +176,12 @@ pwm_main(int argc, char *argv[]) case 'p': pwm_value = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad PWM value provided"); + usage("BAD PWM VAL"); break; case 'r': alt_rate = strtoul(optarg, &ep, 0); if (*ep != '\0') - usage("bad alternative rate provided"); + usage("BAD rate VAL"); break; default: break; @@ -189,7 +189,7 @@ pwm_main(int argc, char *argv[]) } if (print_verbose && set_mask > 0) { - warnx("Chose channels: "); + warnx("Channels: "); printf(" "); for (unsigned i = 0; i Date: Mon, 17 Nov 2014 14:07:13 +0100 Subject: Fix output of ver hwcmd call --- src/systemcmds/ver/ver.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c index c794f5819..2ead3e632 100644 --- a/src/systemcmds/ver/ver.c +++ b/src/systemcmds/ver/ver.c @@ -82,8 +82,8 @@ int ver_main(int argc, char *argv[]) if (ret == 0) { printf("ver hwcmp match: %s\n", HW_ARCH); - return ret; } + return ret; } else { errx(1, "Not enough arguments, try 'ver hwcmp PX4FMU_V2'"); -- cgit v1.2.3 From f20f85f0e3c61ce754fd6d9d73745eaa925b3b04 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 17 Nov 2014 14:07:33 +0100 Subject: Do not spam filter resets in static mode --- src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 685f5e12f..00900c995 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -613,8 +613,11 @@ FixedwingEstimator::check_filter_state() warn_index = max_warn_index; } - warnx("reset: %s", feedback[warn_index]); - mavlink_log_critical(_mavlink_fd, "[ekf check] %s", feedback[warn_index]); + // Do not warn about accel offset if we have no position updates + if (!(warn_index == 5 && _ekf->staticMode)) { + warnx("reset: %s", feedback[warn_index]); + mavlink_log_critical(_mavlink_fd, "[ekf check] %s", feedback[warn_index]); + } } struct estimator_status_report rep; -- cgit v1.2.3 From 41fe04776f362cf9f0fae6451550df8d5eaf8d99 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 17 Nov 2014 14:59:36 +0100 Subject: Fix up stack sizes --- src/modules/bottle_drop/bottle_drop.cpp | 2 +- src/modules/bottle_drop/module.mk | 2 ++ src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 2 +- src/modules/mavlink/mavlink_main.cpp | 2 +- src/modules/navigator/navigator_main.cpp | 2 +- 5 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/modules/bottle_drop/bottle_drop.cpp b/src/modules/bottle_drop/bottle_drop.cpp index 6d24e5d2d..e0bcbc6e9 100644 --- a/src/modules/bottle_drop/bottle_drop.cpp +++ b/src/modules/bottle_drop/bottle_drop.cpp @@ -223,7 +223,7 @@ BottleDrop::start() _main_task = task_spawn_cmd("bottle_drop", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT + 15, - 2048, + 1500, (main_t)&BottleDrop::task_main_trampoline, nullptr); diff --git a/src/modules/bottle_drop/module.mk b/src/modules/bottle_drop/module.mk index 960228879..df9f5473b 100644 --- a/src/modules/bottle_drop/module.mk +++ b/src/modules/bottle_drop/module.mk @@ -41,3 +41,5 @@ SRCS = bottle_drop.cpp \ bottle_drop_params.c MAXOPTIMIZATION = -Os + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 00900c995..e7805daa9 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -1560,7 +1560,7 @@ FixedwingEstimator::start() _estimator_task = task_spawn_cmd("ekf_att_pos_estimator", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 5000, + 7500, (main_t)&FixedwingEstimator::task_main_trampoline, nullptr); diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index c251dd3b2..fb9f65cf5 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1636,7 +1636,7 @@ Mavlink::start(int argc, char *argv[]) task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2900, + 2800, (main_t)&Mavlink::start_helper, (const char **)argv); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 3ca6ac2c0..10a4ee88f 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -499,7 +499,7 @@ Navigator::start() _navigator_task = task_spawn_cmd("navigator", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT + 20, - 2000, + 1800, (main_t)&Navigator::task_main_trampoline, nullptr); -- cgit v1.2.3 From 97a1410ec99e880207e4ee6d2a03451c2e11f4cf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Nov 2014 09:03:50 +0100 Subject: Toolchain: Allow GCC 4.7 and 4.8 variants --- makefiles/toolchain_gnu-arm-eabi.mk | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 71c7fb49f..84e5cd08a 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -50,11 +50,11 @@ OBJDUMP = $(CROSSDEV)objdump # Check if the right version of the toolchain is available # -CROSSDEV_VER_SUPPORTED = 4.7 +CROSSDEV_VER_SUPPORTED = 4.7.4 4.7.5 4.7.6 4.8.4 CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion) -ifeq (,$(findstring $(CROSSDEV_VER_SUPPORTED),$(CROSSDEV_VER_FOUND))) -$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of $(CROSSDEV_VER_SUPPORTED).x) +ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED))) +$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of one in: $(CROSSDEV_VER_SUPPORTED)) endif -- cgit v1.2.3