Replay: correct vehicle detection from MSG messages
This commit is contained in:
parent
db833a6473
commit
2b05f6e2b1
@ -14,7 +14,7 @@ void MsgHandler_MSG::process_message(uint8_t *msg)
|
||||
ahrs.set_vehicle_class(AHRS_VEHICLE_FIXED_WING);
|
||||
ahrs.set_fly_forward(true);
|
||||
} else if (strncmp(msg_text, "ArduCopter", strlen("ArduCopter")) == 0 ||
|
||||
strncmp(msg_text, "APM:Copter", strlen("APM:Copter"))) {
|
||||
strncmp(msg_text, "APM:Copter", strlen("APM:Copter")) == 0) {
|
||||
vehicle = VehicleType::VEHICLE_COPTER;
|
||||
::printf("Detected Copter\n");
|
||||
ahrs.set_vehicle_class(AHRS_VEHICLE_COPTER);
|
||||
|
Loading…
Reference in New Issue
Block a user