3 Commits

Author SHA1 Message Date
Oleg Kalachev
af86699eb3 Add support form arm/disarm mavlink command 2025-07-30 14:36:57 +03:00
Oleg Kalachev
496888903f Make rc loss timeout longer 2025-07-29 22:04:19 +03:00
Oleg Kalachev
3cde9e69c4 Fixes 2025-07-29 22:04:04 +03:00
3 changed files with 12 additions and 4 deletions

View File

@@ -79,7 +79,7 @@ void interpretControls() {
if (mode == STAB) {
float yawTarget = attitudeTarget.getYaw();
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or yaw rate is set
if (invalid(yawTarget) || controlYaw != 0) yawTarget = attitude.getYaw(); // reset yaw target if NAN or pilot commands yaw rate
attitudeTarget = Quaternion::fromEuler(Vector(controlRoll * tiltMax, controlPitch * tiltMax, yawTarget));
ratesExtra = Vector(0, 0, -controlYaw * maxRate.z); // positive yaw stick means clockwise rotation in FLU
}
@@ -139,7 +139,7 @@ void controlTorque() {
if (!torqueTarget.valid()) return; // skip torque control
if (!armed || thrustTarget < 0.05) {
memset(motors, 0, sizeof(motors));
memset(motors, 0, sizeof(motors)); // stop motors if no thrust
return;
}

View File

@@ -3,7 +3,9 @@
// Fail-safe functions
#define RC_LOSS_TIMEOUT 0.2
#include "util.h"
#define RC_LOSS_TIMEOUT 0.5
#define DESCEND_TIME 3.0 // time to descend from full throttle to zero
extern double controlTime;
@@ -28,7 +30,7 @@ void autoFailsafe() {
static float roll, pitch, yaw, throttle;
if (roll != controlRoll || pitch != controlPitch || yaw != controlYaw || abs(throttle - controlThrottle) > 0.05) {
if (mode == AUTO && !isfinite(controlMode)) {
if (mode == AUTO && invalid(controlMode)) {
mode = STAB; // regain control to the pilot
}
}

View File

@@ -231,6 +231,12 @@ void handleMavlink(const void *_msg) {
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
if (m.command == MAV_CMD_COMPONENT_ARM_DISARM) {
armed = m.param1 == 1;
mavlink_msg_command_ack_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &ack, m.command, MAV_RESULT_ACCEPTED, UINT8_MAX, 0, msg.sysid, msg.compid);
sendMessage(&ack);
}
}
}