Rename RC_CHANNEL_AUX to RC_CHANNEL_ARMED

This commit is contained in:
Oleg Kalachev 2024-01-19 05:19:41 +03:00
parent 26a028ff66
commit ed6d09061b
6 changed files with 9 additions and 9 deletions

View File

@ -73,12 +73,12 @@ void doCommand(String& command, String& value) {
Serial.printf("acc: %f %f %f\n", acc.x, acc.y, acc.z);
printIMUCal();
} else if (command == "rc") {
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d aux %d mode %d\n",
Serial.printf("Raw: throttle %d yaw %d pitch %d roll %d armed %d mode %d\n",
channels[RC_CHANNEL_THROTTLE], channels[RC_CHANNEL_YAW], channels[RC_CHANNEL_PITCH],
channels[RC_CHANNEL_ROLL], channels[RC_CHANNEL_AUX], channels[RC_CHANNEL_MODE]);
Serial.printf("Control: throttle %f yaw %f pitch %f roll %f aux %f mode %f\n",
channels[RC_CHANNEL_ROLL], channels[RC_CHANNEL_ARMED], channels[RC_CHANNEL_MODE]);
Serial.printf("Control: throttle %f yaw %f pitch %f roll %f armed %f mode %f\n",
controls[RC_CHANNEL_THROTTLE], controls[RC_CHANNEL_YAW], controls[RC_CHANNEL_PITCH],
controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_AUX], controls[RC_CHANNEL_MODE]);
controls[RC_CHANNEL_ROLL], controls[RC_CHANNEL_ARMED], controls[RC_CHANNEL_MODE]);
Serial.printf("Mode: %s\n", getModeName());
} else if (command == "mot") {
Serial.printf("MOTOR front-right %f front-left %f rear-right %f rear-left %f\n",

View File

@ -77,7 +77,7 @@ void interpretRC() {
mode = STAB;
}
armed = controls[RC_CHANNEL_THROTTLE] >= 0.05 && controls[RC_CHANNEL_AUX] >= 0.5;
armed = controls[RC_CHANNEL_THROTTLE] >= 0.05 && controls[RC_CHANNEL_ARMED] >= 0.5;
thrustTarget = controls[RC_CHANNEL_THROTTLE];
if (mode == ACRO) {

View File

@ -15,7 +15,7 @@
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
#define RC_CHANNEL_YAW 3
#define RC_CHANNEL_AUX 4
#define RC_CHANNEL_ARMED 4
#define RC_CHANNEL_MODE 5
#define MOTOR_REAR_LEFT 0

View File

@ -90,7 +90,7 @@ void handleMavlink(const void *_msg) {
controls[RC_CHANNEL_ROLL] = manualControl.y / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_YAW] = manualControl.r / 1000.0f * MAVLINK_CONTROL_SCALE;
controls[RC_CHANNEL_MODE] = 1; // STAB mode
controls[RC_CHANNEL_AUX] = 1; // armed
controls[RC_CHANNEL_ARMED] = 1; // armed
}
}

View File

@ -15,7 +15,7 @@ const int channelMaxOverride[] = {27090, 27090, 27090, 27090, 0, 1};
#define RC_CHANNEL_PITCH 1
#define RC_CHANNEL_THROTTLE 2
#define RC_CHANNEL_YAW 3
#define RC_CHANNEL_AUX 4
#define RC_CHANNEL_ARMED 4
#define RC_CHANNEL_MODE 5
SDL_Joystick *joystick;

View File

@ -69,7 +69,7 @@ public:
// read rc
readRC();
controls[RC_CHANNEL_MODE] = 1; // 0 acro, 1 stab
controls[RC_CHANNEL_AUX] = 1; // armed
controls[RC_CHANNEL_ARMED] = 1; // armed
estimate();