diff --git a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc index c454a612096ad878ecb0b857951b5b1e00c4d230..4ba9430c75b96a0d11360922896531c3b7e71b5b 100644 --- a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc +++ b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc @@ -381,7 +381,7 @@ ESP8266ComponentController::_processTimeout() //----------------------------------------------------------------------------- void -ESP8266ComponentController::_mavCommandResult(int vehicleId, int component, MAV_CMD command, MAV_RESULT result, bool noReponseFromVehicle) +ESP8266ComponentController::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle) { Q_UNUSED(vehicleId); Q_UNUSED(noReponseFromVehicle); diff --git a/src/AutoPilotPlugins/Common/ESP8266ComponentController.h b/src/AutoPilotPlugins/Common/ESP8266ComponentController.h index 64c831fb15d9d4042f0f9a2c2ac7e95a0d11dc4a..afba9939c4d1c387049dab219fb4dd05e8746704 100644 --- a/src/AutoPilotPlugins/Common/ESP8266ComponentController.h +++ b/src/AutoPilotPlugins/Common/ESP8266ComponentController.h @@ -83,7 +83,7 @@ signals: private slots: void _processTimeout (); - void _mavCommandResult(int vehicleId, int component, MAV_CMD command, MAV_RESULT result, bool noReponseFromVehicle); + void _mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle); void _ssidChanged (QVariant value); void _passwordChanged (QVariant value); void _baudChanged (QVariant value); diff --git a/src/Vehicle/MAVLinkLogManager.cc b/src/Vehicle/MAVLinkLogManager.cc index 5014150e07fb29ff3110205b495d6b20e5a20e8a..567b7d935df7b1d952866449f475d7928d3bb163 100644 --- a/src/Vehicle/MAVLinkLogManager.cc +++ b/src/Vehicle/MAVLinkLogManager.cc @@ -769,7 +769,7 @@ MAVLinkLogManager::_mavlinkLogData(Vehicle* /*vehicle*/, uint8_t /*target_system //----------------------------------------------------------------------------- void -MAVLinkLogManager::_mavCommandResult(int vehicleId, int component, MAV_CMD command, MAV_RESULT result, bool noReponseFromVehicle) +MAVLinkLogManager::_mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle) { Q_UNUSED(vehicleId); Q_UNUSED(component); diff --git a/src/Vehicle/MAVLinkLogManager.h b/src/Vehicle/MAVLinkLogManager.h index ae8604121595233a2fec5afbd356b7c058be421f..dd1051542acb70e828403307d74d0f1e8b632d78 100644 --- a/src/Vehicle/MAVLinkLogManager.h +++ b/src/Vehicle/MAVLinkLogManager.h @@ -172,7 +172,7 @@ private slots: void _activeVehicleChanged (Vehicle* vehicle); void _mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked); void _armedChanged (bool armed); - void _mavCommandResult (int vehicleId, int component, MAV_CMD command, MAV_RESULT result, bool noReponseFromVehicle); + void _mavCommandResult (int vehicleId, int component, int command, int result, bool noReponseFromVehicle); private: bool _sendLog (const QString& logFile); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 2501a7acd64731c2f0967512cf0c23f772f7bf64..fd19666a2cdd893d736c73ef38e4a7daf896f43e 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -664,7 +664,7 @@ signals: /// @param command MAV_CMD Command which was sent /// @param result MAV_RESULT returned in ack /// @param noResponseFromVehicle true: vehicle did not respond to command, false: vehicle responsed, MAV_RESULT in result - void mavCommandResult(int vehicleId, int component, MAV_CMD command, MAV_RESULT result, bool noReponseFromVehicle); + void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle); private slots: void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);