diff --git a/src/ardupilot/ArduPilotProtocol.cpp b/src/ardupilot/ArduPilotProtocol.cpp index 1afe5b6d..1a37ea0a 100644 --- a/src/ardupilot/ArduPilotProtocol.cpp +++ b/src/ardupilot/ArduPilotProtocol.cpp @@ -32,9 +32,6 @@ void ArduPilotProtocol::initArduPilotServer(SingleClientWSServer& websocketServe ardupilot_protocol->addMessageHandler( "orientation", std::bind(&ArduPilotProtocol::handleIMURequest, this, _1), validateIMURequest); - ardupilot_protocol->addMessageHandler( - "heading", std::bind(&ArduPilotProtocol::handleHeadingRequest, this, _1), - validateHeadingRequest); ardupilot_protocol->addConnectionHandler( std::bind(&ArduPilotProtocol::clientConnected, this)); ardupilot_protocol->addDisconnectionHandler( @@ -89,16 +86,6 @@ void ArduPilotProtocol::handleIMURequest(const json& j) { _lastOrientation = util::eulerAnglesToQuat(rpy); } -bool ArduPilotProtocol::validateHeadingRequest(const json& j) { - return util::validateKey(j, "heading", val_t::number_float); -} - -void ArduPilotProtocol::handleHeadingRequest(const json& j) { - int heading = j["heading"]; - std::lock_guard lock(_lastHeadingMutex); - _lastHeading = heading; -} - DataPoint ArduPilotProtocol::getGPS() { std::unique_lock lock(_lastGPSMutex); return _lastGPS; @@ -109,11 +96,6 @@ DataPoint ArduPilotProtocol::getIMU() { return _lastOrientation; } -DataPoint ArduPilotProtocol::getHeading() { - std::unique_lock lock(_lastHeadingMutex); - return _lastHeading; -} - bool ArduPilotProtocol::isArduPilotConnected() { std::unique_lock lock(_connectionMutex); return _arduPilotProtocolConnected; diff --git a/src/ardupilot/ArduPilotProtocol.h b/src/ardupilot/ArduPilotProtocol.h index ae0abb84..ab0166e6 100644 --- a/src/ardupilot/ArduPilotProtocol.h +++ b/src/ardupilot/ArduPilotProtocol.h @@ -31,12 +31,6 @@ class ArduPilotProtocol { */ robot::types::DataPoint getIMU(); - /* @brief Gets the last reported heading (degrees) - * - * @return Last reported heading - */ - robot::types::DataPoint getHeading(); - private: /* @brief Validates GPS request * @@ -54,14 +48,6 @@ class ArduPilotProtocol { */ static bool validateIMURequest(const nlohmann::json& j); - /* @brief Validates heading request - * - * @param json message - * - * @return True if message is valid, false otherwise - */ - static bool validateHeadingRequest(const nlohmann::json& j); - /* @brief Destructures GPS json message and updates last reported GPS values * * @param json message @@ -74,12 +60,6 @@ class ArduPilotProtocol { */ void handleIMURequest(const nlohmann::json& j); - /* @brief Destructures heading json message and updates last reported GPS values - * - * @param json message - */ - void handleHeadingRequest(const nlohmann::json& j); - /* @brief Checks if the ArduPilotProtocol is connected * * @return True if connected, false if not connected @@ -101,9 +81,6 @@ class ArduPilotProtocol { std::mutex _connectionMutex; bool _arduPilotProtocolConnected; - std::mutex _lastHeadingMutex; - robot::types::DataPoint _lastHeading; - std::mutex _lastGPSMutex; robot::types::DataPoint _lastGPS;