diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 8385c8904f..0542bf1a5b 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -527,6 +527,9 @@ void AP_GPS::detect_instance(uint8_t instance) dstate->current_baud = 0; } uint32_t baudrate = _baudrates[dstate->current_baud]; + if(_type[instance] == GPS_TYPE_SINO || _type[instance] == GPS_TYPE_NMEA || _type[instance] == GPS_TYPE_UNICO){ + baudrate = 115200U; + } _port[instance]->begin(baudrate); _port[instance]->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); dstate->last_baud_change_ms = now; @@ -537,7 +540,7 @@ void AP_GPS::detect_instance(uint8_t instance) }else if (_type[instance] == GPS_TYPE_SINO) { send_blob_start(instance, AP_GPS_NMEA_SINO_INIT_STRING, strlen(AP_GPS_NMEA_SINO_INIT_STRING)); }else if (_type[instance] == GPS_TYPE_UNICO) { - send_blob_start(instance, AP_GPS_NMEA_UNICORE_INIT_STRING, strlen(AP_GPS_NMEA_UNICORE_INIT_STRING)); + send_blob_start(instance, AP_GPS_NMEA_UNICORE_INIT_STRING, strlen(AP_GPS_NMEA_UNICORE_INIT_STRING)); }else { send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob)); } diff --git a/rs100.sh b/rs100.sh index 461bcd3e2f..7612237f19 100755 --- a/rs100.sh +++ b/rs100.sh @@ -1,3 +1,3 @@ ./waf configure --board rs100 ./waf copter -cp ./build/rs100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/rs100-v4.1.16-5.px4 +cp ./build/rs100/bin/arducopter.apj /mnt/f/_01-work/100\=data/固件/编译/rs100-v4.1.18.px4