From c4899e4adc28e8bd178de11d8361d814bbd67125 Mon Sep 17 00:00:00 2001 From: Abhay D Date: Thu, 19 Oct 2023 18:14:59 -0700 Subject: [PATCH] Fix broken log statements --- src/network/MissionControlProtocol.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/network/MissionControlProtocol.cpp b/src/network/MissionControlProtocol.cpp index 03e52e2f0..1d0c0dfd0 100644 --- a/src/network/MissionControlProtocol.cpp +++ b/src/network/MissionControlProtocol.cpp @@ -189,8 +189,8 @@ void MissionControlProtocol::handleJointPowerRequest(const json& j) { void MissionControlProtocol::sendRoverPos() { 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())); + log(LOG_DEBUG, "imu_valid=%s, gps_valid=%s\n", util::to_string(imu.isValid()).c_str(), + util::to_string(gps.isValid()).c_str()); if (imu.isValid()) { auto rpy = imu.getData(); Eigen::Quaterniond quat(Eigen::AngleAxisd(rpy.roll, Eigen::Vector3d::UnitX()) *