diff --git a/.clang-format b/.clang-format index 00334c3e6..8614cd04a 100644 --- a/.clang-format +++ b/.clang-format @@ -17,3 +17,4 @@ IncludeCategories: Priority: 3 IndentCaseLabels: true PointerAlignment: Left +AlwaysBreakTemplateDeclarations: Yes diff --git a/src/ardupilot/ArduPilotInterface.cpp b/src/ardupilot/ArduPilotInterface.cpp index 4448f4bff..349bbede5 100644 --- a/src/ardupilot/ArduPilotInterface.cpp +++ b/src/ardupilot/ArduPilotInterface.cpp @@ -25,11 +25,7 @@ DataPoint readGPSCoords() { } // namespace gps namespace robot { -DataPoint readIMUHeading() { - auto imu_heading = ardupilot_protocol->getIMU(); - if (imu_heading.isValid()) { - return DataPoint(imu_heading.getTime(), imu_heading.getData().yaw); - } - return DataPoint(); +DataPoint readIMU() { + return ardupilot_protocol->getIMU(); } } // namespace robot diff --git a/src/ardupilot/ArduPilotProtocol.cpp b/src/ardupilot/ArduPilotProtocol.cpp index 18f00dd39..dd0b2d869 100644 --- a/src/ardupilot/ArduPilotProtocol.cpp +++ b/src/ardupilot/ArduPilotProtocol.cpp @@ -65,7 +65,7 @@ bool ArduPilotProtocol::validateGPSRequest(const json& j) { void ArduPilotProtocol::handleGPSRequest(const json& j) { double lat = j["lat"]; - double lon = j["lat"]; + double lon = j["lon"]; { std::lock_guard lock(_lastGPSMutex); _lastGPS = gpscoords_t{lat, lon}; diff --git a/src/network/MissionControlProtocol.cpp b/src/network/MissionControlProtocol.cpp index 53a992761..4ce140832 100644 --- a/src/network/MissionControlProtocol.cpp +++ b/src/network/MissionControlProtocol.cpp @@ -4,6 +4,7 @@ #include "../Globals.h" #include "../base64/base64_img.h" #include "../log.h" +#include "../utils/core.h" #include "../utils/json.h" #include "../world_interface/data.h" #include "../world_interface/world_interface.h" @@ -185,24 +186,32 @@ void MissionControlProtocol::handleJointPowerRequest(const json& j) { } void MissionControlProtocol::sendRoverPos() { - auto heading = robot::readIMUHeading(); - auto gps = robot::readGPS(); - if (gps.isValid() && heading.isValid()) { - double orientX = 0.0; - double orientY = 0.0; - double orientZ = std::sin(heading.getData() / 2); - double orientW = std::cos(heading.getData() / 2); - double posX = gps.getData()[0]; - double posY = gps.getData()[1]; + auto imu = robot::readIMU(); + auto gps = gps::readGPSCoords(); + log(LOG_DEBUG, "imu_valid=%d, gps_valid=%d\n", util::to_string(imu.isValid()), + util::to_string(gps.isValid())); + if (imu.isValid()) { + auto rpy = imu.getData(); + Eigen::Quaterniond quat(Eigen::AngleAxisd(rpy.roll, Eigen::Vector3d::UnitX()) * + Eigen::AngleAxisd(rpy.pitch, Eigen::Vector3d::UnitY()) * + Eigen::AngleAxisd(rpy.yaw, Eigen::Vector3d::UnitZ())); + double posX = 0, posY = 0; + if (gps.isValid()) { + posX = gps.getData().lon; + posY = gps.getData().lat; + } double posZ = 0.0; - double gpsRecency = util::durationToSec(dataclock::now() - gps.getTime()); - double headingRecency = util::durationToSec(dataclock::now() - heading.getTime()); - double recency = std::max(gpsRecency, headingRecency); + double imuRecency = util::durationToSec(dataclock::now() - imu.getTime()); + double recency = imuRecency; + if (gps.isValid()) { + double gpsRecency = util::durationToSec(dataclock::now() - gps.getTime()); + recency = std::max(recency, gpsRecency); + } json msg = {{"type", ROVER_POS_REP_TYPE}, - {"orientW", orientW}, - {"orientX", orientX}, - {"orientY", orientY}, - {"orientZ", orientZ}, + {"orientW", quat.w()}, + {"orientX", quat.x()}, + {"orientY", quat.y()}, + {"orientZ", quat.z()}, {"posX", posX}, {"posY", posY}, {"posZ", posZ}, diff --git a/src/utils/core.cpp b/src/utils/core.cpp index d0fe66b32..96c8e4438 100644 --- a/src/utils/core.cpp +++ b/src/utils/core.cpp @@ -6,6 +6,11 @@ bool almostEqual(double a, double b, double threshold) { return std::abs(a - b) < threshold; } +template <> +std::string to_string(const bool& val) { + return val ? "true" : "false"; +} + frozen::string freezeStr(const std::string& str) { return frozen::string(str.c_str(), str.size()); } diff --git a/src/utils/core.h b/src/utils/core.h index 809bd9dfe..6fc5bc2cf 100644 --- a/src/utils/core.h +++ b/src/utils/core.h @@ -44,10 +44,20 @@ std::unordered_set keySet(const std::unordered_map& input) { * @return A string representation of that value, as a std::string. The exact representation of * the value is up to the implementation. */ -template std::string to_string(const T& val) { +template +std::string to_string(const T& val) { return std::to_string(val); } +/** + * @brief Converts a boolean to a string. + * + * @param val The value to get the string representation of. + * @return "true" iff val, otherwise "false". + */ +template <> +std::string to_string(const bool& val); + /** * @brief Convert the given std::string to a frozen::string. */ diff --git a/src/world_interface/data.h b/src/world_interface/data.h index 2f4784d24..550999074 100644 --- a/src/world_interface/data.h +++ b/src/world_interface/data.h @@ -6,6 +6,7 @@ #include #include #include +#include #include #include @@ -29,7 +30,8 @@ using dataclock = std::chrono::steady_clock; /** @brief A point in time as measured by dataclock */ using datatime_t = std::chrono::time_point; -template class DataPoint; +template +class DataPoint; /** * @brief A data structure that represents when each landmark was seen. @@ -108,7 +110,8 @@ constexpr auto name_to_jointid = frozen::make_unordered_map class DataPoint { +template +class DataPoint { public: /** * @brief Construct an invalid DataPoint, holding no data @@ -200,6 +203,24 @@ template class DataPoint { return isValid() ? getData() : defaultData; } + /** + * @brief Transforms the data in this datapoint by the given function. + * + * @tparam F A callable type that accepts @p T and outputs some other type. + * @param f The function that transforms data. + * @return DataPoint> A new datapoint that holds + * the output of `f(getData())` and has the same timestamp as this datapoint + * if it's valid, otherwise an empty datapoint. + */ + template + DataPoint> transform(const F& f) { + if (isValid()) { + return DataPoint>(getTime(), f(getData())); + } else { + return {}; + } + } + private: /** * @brief The time and measurement data. diff --git a/src/world_interface/gps_common_interface.cpp b/src/world_interface/gps_common_interface.cpp index 00e8f99d8..7947d236e 100644 --- a/src/world_interface/gps_common_interface.cpp +++ b/src/world_interface/gps_common_interface.cpp @@ -10,6 +10,10 @@ static std::optional converter; namespace robot { +DataPoint readIMUHeading() { + return readIMU().transform([](const navtypes::eulerangles_t& e) { return e.yaw; }); +} + DataPoint readGPS() { DataPoint coords = gps::readGPSCoords(); if (!coords) { diff --git a/src/world_interface/noop_world.cpp b/src/world_interface/noop_world.cpp index f08c40c81..b5b621283 100644 --- a/src/world_interface/noop_world.cpp +++ b/src/world_interface/noop_world.cpp @@ -43,7 +43,7 @@ landmarks_t readLandmarks() { return landmarks_t{}; } -DataPoint readIMUHeading() { +DataPoint readIMU() { return {}; } diff --git a/src/world_interface/simulator_interface.cpp b/src/world_interface/simulator_interface.cpp index 2c6bc7053..5152bd0d9 100644 --- a/src/world_interface/simulator_interface.cpp +++ b/src/world_interface/simulator_interface.cpp @@ -41,8 +41,8 @@ const std::map motorNameMap = { {motorid_t::wrist, "wrist"}, {motorid_t::hand, "hand"}}; -DataPoint lastHeading; -std::mutex headingMutex; +DataPoint lastAttitude; +std::mutex attitudeMutex; DataPoint lastGPS; std::mutex gpsMutex; @@ -149,8 +149,12 @@ void handleIMU(json msg) { double qw = msg["w"]; double heading = util::quatToHeading(qw, qx, qy, qz); - std::lock_guard guard(headingMutex); - lastHeading = {heading}; + Eigen::Quaterniond q(qw, qx, qy, qz); + q.normalize(); + Eigen::Vector3d euler = q.toRotationMatrix().eulerAngles(0, 1, 2); + std::lock_guard guard(attitudeMutex); + lastAttitude = + navtypes::eulerangles_t{.roll = euler(0), .pitch = euler(1), .yaw = euler(2)}; } void handleCamFrame(json msg) { @@ -364,9 +368,9 @@ DataPoint readVisualOdomVel() { return DataPoint{}; } -DataPoint readIMUHeading() { - std::lock_guard guard(headingMutex); - return lastHeading; +DataPoint readIMU() { + std::lock_guard guard(attitudeMutex); + return lastAttitude; } DataPoint getTruePose() { diff --git a/src/world_interface/world_interface.h b/src/world_interface/world_interface.h index 83dcded77..a737cae54 100644 --- a/src/world_interface/world_interface.h +++ b/src/world_interface/world_interface.h @@ -165,6 +165,17 @@ types::DataPoint readGPS(); */ types::DataPoint readIMUHeading(); +/** + * @brief Read the rover attitude from the IMU. + * + * Euler angles are in radians, in RPY format (i.e. XYZ extrinsic) + * + * @see https://en.wikipedia.org/wiki/Euler_angles#Tait%E2%80%93Bryan_angles + * + * @return types::DataPoint + */ +types::DataPoint readIMU(); + /** * @brief Get the ground truth pose, if available. This is only available in simulation. *