From 9315796020339906d30580892f57abcdc1238b0c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Feb 2014 07:55:22 +0100 Subject: Enable S.BUS TX pin --- nuttx-configs/px4io-v2/include/board.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/nuttx-configs/px4io-v2/include/board.h b/nuttx-configs/px4io-v2/include/board.h index 4b9c90638..17e77918b 100755 --- a/nuttx-configs/px4io-v2/include/board.h +++ b/nuttx-configs/px4io-v2/include/board.h @@ -103,8 +103,6 @@ #define GPIO_USART2_RTS 0xffffffff #undef GPIO_USART2_CK #define GPIO_USART2_CK 0xffffffff -#undef GPIO_USART3_TX -#define GPIO_USART3_TX 0xffffffff #undef GPIO_USART3_CK #define GPIO_USART3_CK 0xffffffff #undef GPIO_USART3_CTS -- cgit v1.2.3 From 500ac69ee46ad582eee5a4321bd53665e17032da Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Feb 2014 08:13:53 +0100 Subject: Build test code for S.BUS output, send test characters once S.BUS1 or S.BUS2 is enabled --- src/modules/px4iofirmware/mixer.cpp | 14 ++++++++++++++ src/modules/px4iofirmware/px4io.h | 2 ++ src/modules/px4iofirmware/sbus.c | 14 +++++++++++++- 3 files changed, 29 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index f39fcf7ec..3eaecc38b 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -254,10 +254,24 @@ mixer_tick(void) for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) up_pwm_servo_set(i, r_page_servos[i]); + /* set S.BUS1 or S.BUS2 outputs */ + if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) + sbus1_output(r_page_servos, PX4IO_SERVO_COUNT); + + if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) + sbus2_output(r_page_servos, PX4IO_SERVO_COUNT); + } else if (mixer_servos_armed && should_always_enable_pwm) { /* set the disarmed servo outputs. */ for (unsigned i = 0; i < PX4IO_SERVO_COUNT; i++) up_pwm_servo_set(i, r_page_servo_disarmed[i]); + + /* set S.BUS1 or S.BUS2 outputs */ + if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) + sbus1_output(r_page_servos, PX4IO_SERVO_COUNT); + + if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) + sbus2_output(r_page_servos, PX4IO_SERVO_COUNT); } } diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index bb224f388..0e9fee8ae 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -218,6 +218,8 @@ extern bool dsm_input(uint16_t *values, uint16_t *num_values); extern void dsm_bind(uint16_t cmd, int pulses); extern int sbus_init(const char *device); extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels); +extern bool sbus1_output(uint16_t *values, uint16_t num_values); +extern bool sbus2_output(uint16_t *values, uint16_t num_values); /** global debug level for isr_debug() */ extern volatile uint8_t debug_level; diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index f6ec542eb..86240d36a 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -93,7 +93,7 @@ int sbus_init(const char *device) { if (sbus_fd < 0) - sbus_fd = open(device, O_RDONLY | O_NONBLOCK); + sbus_fd = open(device, O_RDWR | O_NONBLOCK); if (sbus_fd >= 0) { struct termios t; @@ -117,6 +117,18 @@ sbus_init(const char *device) return sbus_fd; } +bool +sbus1_output(uint16_t *values, uint16_t num_values) +{ + write(sbus_fd, 'A', 1); +} + +bool +sbus2_output(uint16_t *values, uint16_t num_values) +{ + write(sbus_fd, 'B', 1); +} + bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels) { -- cgit v1.2.3 From 85ec7fb40aab728ba477ffd75f48c2c731fb56fa Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Feb 2014 08:47:01 +0100 Subject: test loop --- src/modules/px4iofirmware/sbus.c | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 86240d36a..39230d274 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -114,6 +114,14 @@ sbus_init(const char *device) debug("S.Bus: open failed"); } + ENABLE_SBUS_OUT(true); + + while (1) { + const char* hello = 'HELLO WORLD'; + if (write(sbus_fd, hello, strlen(hello)) != strlen(hello)) + break; + } + return sbus_fd; } -- cgit v1.2.3 From 3bcf34098a9fd07c0693e918396d2e3fde0fa1e8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 12 Feb 2014 08:50:44 +0100 Subject: Fix quotation marks --- src/modules/px4iofirmware/sbus.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 39230d274..6608392d0 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -117,7 +117,7 @@ sbus_init(const char *device) ENABLE_SBUS_OUT(true); while (1) { - const char* hello = 'HELLO WORLD'; + const char* hello = "HELLO WORLD"; if (write(sbus_fd, hello, strlen(hello)) != strlen(hello)) break; } -- cgit v1.2.3 From bc3f95fc07fb01edecfa9147023a354f1f237e92 Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 12 Feb 2014 00:48:15 -0800 Subject: Turn off JTAG completely in a vain attempt to get PB4 free for SBUS enable. --- nuttx-configs/px4io-v2/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig index 4111e70eb..2c63b8819 100755 --- a/nuttx-configs/px4io-v2/nsh/defconfig +++ b/nuttx-configs/px4io-v2/nsh/defconfig @@ -104,7 +104,7 @@ CONFIG_ARMV7M_CMNVECTOR=y # CONFIG_STM32_JTAG_SW_ENABLE - Set JTAG-DP disabled and SW-DP enabled # CONFIG_STM32_DFU=n -CONFIG_STM32_JTAG_FULL_ENABLE=y +CONFIG_STM32_JTAG_FULL_ENABLE=n CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n CONFIG_STM32_JTAG_SW_ENABLE=n -- cgit v1.2.3 From ca2ad0051d2c5a31aa6050cc88f5c7d6c2997036 Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 12 Feb 2014 00:48:53 -0800 Subject: Be more enthusiastic with the sbus enable pin. Still no love. --- src/modules/px4iofirmware/sbus.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 6608392d0..32be93d4c 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -114,12 +114,14 @@ sbus_init(const char *device) debug("S.Bus: open failed"); } - ENABLE_SBUS_OUT(true); + stm32_configgpio(GPIO_SBUS_OENABLE); while (1) { + ENABLE_SBUS_OUT(true); const char* hello = "HELLO WORLD"; if (write(sbus_fd, hello, strlen(hello)) != strlen(hello)) break; + ENABLE_SBUS_OUT(false); } return sbus_fd; -- cgit v1.2.3 From cec6b8925e727710884042f9b45c105aa8c4d5af Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 12 Feb 2014 22:10:45 -0800 Subject: Don't leave all JTAG off... it will make you very sad --- nuttx-configs/px4io-v2/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4io-v2/nsh/defconfig b/nuttx-configs/px4io-v2/nsh/defconfig index 2c63b8819..e6563e587 100755 --- a/nuttx-configs/px4io-v2/nsh/defconfig +++ b/nuttx-configs/px4io-v2/nsh/defconfig @@ -106,7 +106,7 @@ CONFIG_ARMV7M_CMNVECTOR=y CONFIG_STM32_DFU=n CONFIG_STM32_JTAG_FULL_ENABLE=n CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n -CONFIG_STM32_JTAG_SW_ENABLE=n +CONFIG_STM32_JTAG_SW_ENABLE=y # # Individual subsystems can be enabled: -- cgit v1.2.3 From dd432e66032c3cb1cb6f65536c28af1dd9f97317 Mon Sep 17 00:00:00 2001 From: px4dev Date: Wed, 12 Feb 2014 22:11:09 -0800 Subject: Remove the s.bus test loop... makes it very hard to update the firmware. --- src/modules/px4iofirmware/sbus.c | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 32be93d4c..0e7dc621c 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -113,17 +113,6 @@ sbus_init(const char *device) } else { debug("S.Bus: open failed"); } - - stm32_configgpio(GPIO_SBUS_OENABLE); - - while (1) { - ENABLE_SBUS_OUT(true); - const char* hello = "HELLO WORLD"; - if (write(sbus_fd, hello, strlen(hello)) != strlen(hello)) - break; - ENABLE_SBUS_OUT(false); - } - return sbus_fd; } -- cgit v1.2.3 From 6a1f91e6254e14c52b77406b12b76e2a233aedf8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 13 Feb 2014 08:22:05 +0100 Subject: Make SBUS output exclusive --- src/modules/px4iofirmware/mixer.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 3eaecc38b..b175c3bc8 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -255,11 +255,12 @@ mixer_tick(void) up_pwm_servo_set(i, r_page_servos[i]); /* set S.BUS1 or S.BUS2 outputs */ - if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) - sbus1_output(r_page_servos, PX4IO_SERVO_COUNT); - if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) + if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS2_OUT) { sbus2_output(r_page_servos, PX4IO_SERVO_COUNT); + } else if (r_setup_features & PX4IO_P_SETUP_FEATURES_SBUS1_OUT) { + sbus1_output(r_page_servos, PX4IO_SERVO_COUNT); + } } else if (mixer_servos_armed && should_always_enable_pwm) { /* set the disarmed servo outputs. */ -- cgit v1.2.3 From 91c55503a860ffc02a2687c141e2cfc68a43b3cc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 13 Feb 2014 08:25:49 +0100 Subject: Ensure only either S.BUS1 or S.BUS2 can be active at a time --- src/modules/px4iofirmware/registers.c | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 1335f52e1..f78086839 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -462,9 +462,18 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value) #ifdef ENABLE_SBUS_OUT ENABLE_SBUS_OUT(value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT)); - /* disable the conflicting options */ - if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT | PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) { - value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | PX4IO_P_SETUP_FEATURES_ADC_RSSI); + /* disable the conflicting options with SBUS 1 */ + if (value & (PX4IO_P_SETUP_FEATURES_SBUS1_OUT)) { + value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | + PX4IO_P_SETUP_FEATURES_ADC_RSSI | + PX4IO_P_SETUP_FEATURES_SBUS2_OUT); + } + + /* disable the conflicting options with SBUS 2 */ + if (value & (PX4IO_P_SETUP_FEATURES_SBUS2_OUT)) { + value &= ~(PX4IO_P_SETUP_FEATURES_PWM_RSSI | + PX4IO_P_SETUP_FEATURES_ADC_RSSI | + PX4IO_P_SETUP_FEATURES_SBUS1_OUT); } #endif -- cgit v1.2.3 From ee580206b4fd3e79f27db42717987dd414a2a215 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 4 May 2014 14:06:38 +0200 Subject: mavlink: Only sending HIL control commands if the system is actually armed --- src/modules/mavlink/mavlink_messages.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 678ce1645..b538aa28b 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -819,11 +819,11 @@ protected: void send(const hrt_abstime t) { - bool updated = status_sub->update(t); - updated |= pos_sp_triplet_sub->update(t); - updated |= act_sub->update(t); + bool updated = act_sub->update(t); + (void)pos_sp_triplet_sub->update(t); + (void)status_sub->update(t); - if (updated) { + if (updated && (status.arming_state == ARMING_STATE_ARMED)) { /* translate the current syste state to mavlink state and mode */ uint8_t mavlink_state; uint8_t mavlink_base_mode; -- cgit v1.2.3 From 0e31b5935ebefef3b95d7e39dbf5b1435a4942a1 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 4 May 2014 15:01:07 +0200 Subject: remove trailing whitespace --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index b538aa28b..ab733e442 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1353,7 +1353,7 @@ protected: uint8_t orientation = 0; uint8_t covariance = 20; - mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation, + mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation, range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance); } }; -- cgit v1.2.3 From 5f786af8fa428c8ab684251310de6c3fbe795e8f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 4 May 2014 15:02:00 +0200 Subject: mavlink: status is a pointer --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index ab733e442..bef8a5a55 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -823,7 +823,7 @@ protected: (void)pos_sp_triplet_sub->update(t); (void)status_sub->update(t); - if (updated && (status.arming_state == ARMING_STATE_ARMED)) { + if (updated && (status->arming_state == ARMING_STATE_ARMED)) { /* translate the current syste state to mavlink state and mode */ uint8_t mavlink_state; uint8_t mavlink_base_mode; -- cgit v1.2.3 From 41a0f17b4e929a4563cebeff402ce5fdb02771a2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 4 May 2014 19:55:24 +0200 Subject: mc.defaults: MPC_TILTMAX_XXX parameters fixed --- ROMFS/px4fmu_common/init.d/rc.mc_defaults | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.mc_defaults b/ROMFS/px4fmu_common/init.d/rc.mc_defaults index 4db62607a..a8c6dc811 100644 --- a/ROMFS/px4fmu_common/init.d/rc.mc_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.mc_defaults @@ -32,9 +32,9 @@ then param set MPC_Z_VEL_D 0.0 param set MPC_Z_VEL_MAX 3 param set MPC_Z_FF 0.5 - param set MPC_TILT_MAX 1.0 + param set MPC_TILTMAX_AIR 45.0 + param set MPC_TILTMAX_LND 15.0 param set MPC_LAND_SPEED 1.0 - param set MPC_LAND_TILT 0.3 fi set PWM_RATE 400 -- cgit v1.2.3 From 58ae1edc8447628040c8877addc485d41f802ee7 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 5 May 2014 17:10:33 +0200 Subject: ignore .orig files --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index c992dbf5a..afd63e06a 100644 --- a/.gitignore +++ b/.gitignore @@ -38,3 +38,4 @@ tags .tags_sorted_by_file .pydevproject .ropeproject +*.orig -- cgit v1.2.3 From df6a0d5a1a4f528e5ba22747d7a4587b7a2263c4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 6 May 2014 12:55:39 +0200 Subject: mavlink: Only send the distance sensor message if the topic actually updates --- src/modules/mavlink/mavlink_messages.cpp | 25 +++++++++++++------------ 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index bef8a5a55..9c552515d 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1339,22 +1339,23 @@ protected: void send(const hrt_abstime t) { - (void)range_sub->update(t); + if (range_sub->update(t)) { - uint8_t type; + uint8_t type; - switch (range->type) { - case RANGE_FINDER_TYPE_LASER: - type = MAV_DISTANCE_SENSOR_LASER; - break; - } + switch (range->type) { + case RANGE_FINDER_TYPE_LASER: + type = MAV_DISTANCE_SENSOR_LASER; + break; + } - uint8_t id = 0; - uint8_t orientation = 0; - uint8_t covariance = 20; + uint8_t id = 0; + uint8_t orientation = 0; + uint8_t covariance = 20; - mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation, - range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance); + mavlink_msg_distance_sensor_send(_channel, range->timestamp / 1000, type, id, orientation, + range->minimum_distance*100, range->maximum_distance*100, range->distance*100, covariance); + } } }; -- cgit v1.2.3 From 1d6b9fae037422f4c61bdd7ee1a5ea0803a59726 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 6 May 2014 14:57:06 +0200 Subject: Fix in-air restarts, protect against an external MAVLink sender exploiting the restart mechanism --- src/drivers/px4io/px4io.cpp | 24 ++++++++++++++++++++---- src/modules/commander/commander.cpp | 5 +++++ src/modules/mavlink/mavlink_receiver.cpp | 6 ++++++ 3 files changed, 31 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 8458c2fdb..aec6dd3b7 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -683,6 +683,25 @@ PX4IO::init() /* send command to arm system via command API */ vehicle_command_s cmd; + /* send this to itself */ + param_t sys_id_param = param_find("MAV_SYS_ID"); + param_t comp_id_param = param_find("MAV_COMP_ID"); + + int32_t sys_id; + int32_t comp_id; + + if (param_get(sys_id_param, &sys_id)) { + errx(1, "PRM SYSID"); + } + + if (param_get(comp_id_param, &comp_id)) { + errx(1, "PRM CMPID"); + } + + cmd.target_system = sys_id; + cmd.target_component = comp_id; + cmd.source_system = sys_id; + cmd.source_component = comp_id; /* request arming */ cmd.param1 = 1.0f; cmd.param2 = 0; @@ -692,10 +711,7 @@ PX4IO::init() cmd.param6 = 0; cmd.param7 = 0; cmd.command = VEHICLE_CMD_COMPONENT_ARM_DISARM; - // cmd.target_system = status.system_id; - // cmd.target_component = status.component_id; - // cmd.source_system = status.system_id; - // cmd.source_component = status.component_id; + /* ask to confirm command */ cmd.confirmation = 1; diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 53ed34f46..141b371b3 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -484,6 +484,11 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) { mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1); } else { + + // Flick to inair restore first if this comes from an onboard system + if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) { + status->arming_state = ARMING_STATE_IN_AIR_RESTORE; + } transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command"); if (arming_res == TRANSITION_DENIED) { mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd"); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 7c93c1c00..64fc41838 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -217,6 +217,12 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) _mavlink->_task_should_exit = true; } else { + + if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) { + warnx("ignoring CMD spoofed with same SYS/COMP ID"); + return; + } + struct vehicle_command_s vcmd; memset(&vcmd, 0, sizeof(vcmd)); -- cgit v1.2.3