Skip to content

Commit

Permalink
Remove heading messages from ArdupilotProtocol (#323)
Browse files Browse the repository at this point in the history
  • Loading branch information
abhaybd authored May 13, 2024
1 parent 5a26ec4 commit 862ae89
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 41 deletions.
18 changes: 0 additions & 18 deletions src/ardupilot/ArduPilotProtocol.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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(
Expand Down Expand Up @@ -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<gpscoords_t> ArduPilotProtocol::getGPS() {
std::unique_lock<std::mutex> lock(_lastGPSMutex);
return _lastGPS;
Expand All @@ -109,11 +96,6 @@ DataPoint<Eigen::Quaterniond> ArduPilotProtocol::getIMU() {
return _lastOrientation;
}

DataPoint<int> ArduPilotProtocol::getHeading() {
std::unique_lock<std::mutex> lock(_lastHeadingMutex);
return _lastHeading;
}

bool ArduPilotProtocol::isArduPilotConnected() {
std::unique_lock<std::mutex> lock(_connectionMutex);
return _arduPilotProtocolConnected;
Expand Down
23 changes: 0 additions & 23 deletions src/ardupilot/ArduPilotProtocol.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,6 @@ class ArduPilotProtocol {
*/
robot::types::DataPoint<Eigen::Quaterniond> getIMU();

/* @brief Gets the last reported heading (degrees)
*
* @return Last reported heading
*/
robot::types::DataPoint<int> getHeading();

private:
/* @brief Validates GPS request
*
Expand All @@ -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
Expand All @@ -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
Expand All @@ -101,9 +81,6 @@ class ArduPilotProtocol {
std::mutex _connectionMutex;
bool _arduPilotProtocolConnected;

std::mutex _lastHeadingMutex;
robot::types::DataPoint<int> _lastHeading;

std::mutex _lastGPSMutex;
robot::types::DataPoint<navtypes::gpscoords_t> _lastGPS;

Expand Down

0 comments on commit 862ae89

Please sign in to comment.