Skip to content

Commit

Permalink
Implement Loguru (#280)
Browse files Browse the repository at this point in the history
* Switch from log.h to loguru

* Switch from log.h to loguru

* Add -ldl flag

* Inject -ldl flag differently

* Log to file in build directory

* Fix formatting

* Remove newlines from log statements

* Implement "latest" log and switch to ctime

* Reaplce assert with loguru's CHECK

* Implement loguru's CHECK in QuadTreeTest, reformat

* Fix formatting

* Change log verbosity and delete logs older than a week old

* Improve std::filesystem calls

* Fix formatting

* Change time handling and add parsing checks

* Remove seconds conversion and remove redundant log

* Remove/upgrade old log statements for log purging

* Add comment for dateString format clarification

* Make scan output check less verbose
  • Loading branch information
quinnmp authored Nov 15, 2023
1 parent 65d4ee5 commit a01aa7b
Show file tree
Hide file tree
Showing 33 changed files with 330 additions and 355 deletions.
13 changes: 7 additions & 6 deletions src/CAN/CAN.cpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#include "CAN.h"

#include "../log.h"
#include "CANUtils.h"

#include <chrono>
#include <cstring>
#include <loguru.hpp>
#include <memory>
#include <mutex>
#include <shared_mutex>
Expand All @@ -29,7 +29,8 @@ extern "C" {
using robot::types::DataPoint;

// template specialization for hashing pairs
template <typename T1, typename T2> struct std::hash<std::pair<T1, T2>> {
template <typename T1, typename T2>
struct std::hash<std::pair<T1, T2>> {
std::size_t operator()(const std::pair<T1, T2>& pair) const {
auto h1 = std::hash<T1>()(pair.first);
auto h2 = std::hash<T2>()(pair.second);
Expand Down Expand Up @@ -181,7 +182,7 @@ int createCANSocket(std::optional<can::deviceid_t> id) {
std::perror("Failed to get virtual CAN interface index");
return -1;
}
log(LOG_INFO, "Found virtual CAN interface index.\n");
LOG_F(INFO, "Found virtual CAN interface index.");
}

struct sockaddr_can addr;
Expand Down Expand Up @@ -215,7 +216,7 @@ void receiveThreadFn() {
// create dedicated CAN socket for reading
int recvFD = createCANSocket({{devicegroup_t::master, DEVICE_SERIAL_JETSON}});
if (recvFD < 0) {
log(LOG_ERROR, "Unable to open CAN connection!\n");
LOG_F(ERROR, "Unable to open CAN connection!");
return;
}

Expand All @@ -237,7 +238,7 @@ void receiveThreadFn() {
break;

default:
log(LOG_WARN, "Unrecognized CAN packet type: %x\n", packetType);
LOG_F(WARNING, "Unrecognized CAN packet type: %x", packetType);
break;
}
} else {
Expand All @@ -252,7 +253,7 @@ void initCAN() {
std::lock_guard lock(socketMutex);
can_fd = createCANSocket({});
if (can_fd < 0) {
log(LOG_ERROR, "Unable to open CAN connection!\n");
LOG_F(ERROR, "Unable to open CAN connection!");
}

// start thread for recieving CAN packets
Expand Down
12 changes: 9 additions & 3 deletions src/CAN/CANTest.cpp
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
#include "CAN.h"

#include "../log.h"
#include "CANMotor.h"

#include <loguru.hpp>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
Expand All @@ -14,7 +14,13 @@
#include <sys/ioctl.h>
#include <sys/socket.h>

enum class testmode_t { automatic = 0, autoSend = 1, manualSend = 2, fullManual = 3 };
enum class testmode_t
{
automatic = 0,
autoSend = 1,
manualSend = 2,
fullManual = 3
};

constexpr uint8_t serial = 0xA;
constexpr int16_t pwm = 10000;
Expand Down Expand Up @@ -150,7 +156,7 @@ int main(int argc, char* argv[]) {
mode = static_cast<testmode_t>(i);
}

log(LOG_INFO, "Mode=%d\n", static_cast<int>(mode));
LOG_F(INFO, "Mode=%d", static_cast<int>(mode));

switch (mode) {
case testmode_t::automatic:
Expand Down
8 changes: 4 additions & 4 deletions src/CAN/TestIMU.cpp
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
#include "../log.h"
#include "CAN.h"
extern "C" {
#include <HindsightCAN/CANCommon.h>
#include <HindsightCAN/CANSerialNumbers.h>
}

#include <chrono>
#include <loguru.hpp>
#include <thread>

using namespace std::chrono_literals;
Expand All @@ -24,10 +24,10 @@ constexpr can::telemtype_t IMU_DATA_TYPES[] = {
void telemCallback(can::deviceid_t id, can::telemtype_t telemType,
DataPoint<can::telemetry_t> data) {
if (data) {
log(LOG_INFO, "Telemetry: TelemType=%x, Data=%d\n", static_cast<int>(telemType),
data.getData());
LOG_F(INFO, "Telemetry: TelemType=%x, Data=%d", static_cast<int>(telemType),
data.getData());
} else {
log(LOG_INFO, "Telemetry: TelemType=%x, Data=null\n", static_cast<int>(telemType));
LOG_F(INFO, "Telemetry: TelemType=%x, Data=null", static_cast<int>(telemType));
}
}

Expand Down
11 changes: 10 additions & 1 deletion src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,16 @@ FetchContent_Declare(
)
FetchContent_MakeAvailable(HindsightCAN)

FetchContent_Declare(LoguruGitRepo
GIT_REPOSITORY "https://github.com/emilk/loguru"
GIT_TAG "master"
)
# set any loguru compile-time flags before calling MakeAvailable()
set(LOGURU_WITH_STREAMS TRUE)
set(CMAKE_POSITION_INDEPENDENT_CODE ON)
FetchContent_MakeAvailable(LoguruGitRepo) # defines target 'loguru::loguru'
link_libraries(loguru::loguru -ldl)

find_package(Threads REQUIRED)
find_package(OpenCV REQUIRED)

Expand Down Expand Up @@ -136,7 +146,6 @@ target_link_libraries(camera PUBLIC ${OpenCV_LIBS})

# shared library for utility code
add_library(utils SHARED
log.cpp
utils/core.cpp
utils/random.cpp
utils/ScopedTimer.cpp
Expand Down
8 changes: 4 additions & 4 deletions src/LimitCalib.cpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
#include "log.h"
#include "utils/threading.h"
#include "world_interface/real_world_constants.h"
#include "world_interface/world_interface.h"

#include <chrono>
#include <csignal>
#include <loguru.hpp>

using namespace robot;
using namespace std::chrono;
Expand All @@ -22,7 +22,7 @@ void callback(motorid_t motor, const types::DataPoint<LimitSwitchData>& data) {
};

void cleanup(int signum) {
log(LOG_ERROR, "Interrupted!\n");
LOG_F(ERROR, "Interrupted!");
robot::emergencyStop();
exit(0);
}
Expand All @@ -43,7 +43,7 @@ int main() {
robot::addLimitSwitchCallback(entry.first, callback);
}

log(LOG_INFO, "Zero calibrating...\n");
LOG_F(INFO, "Zero calibrating...");

// run motors until latch unlatches
do {
Expand All @@ -52,5 +52,5 @@ int main() {
}
} while (!latch.wait_for(500ms));

log(LOG_INFO, "Done\n");
LOG_F(INFO, "Done");
}
88 changes: 71 additions & 17 deletions src/Rover.cpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
#include "Constants.h"
#include "Globals.h"
#include "log.h"
#include "navtypes.h"
#include "network/MissionControlProtocol.h"
#include "rospub.h"
Expand All @@ -10,7 +9,9 @@
#include <chrono>
#include <csignal>
#include <ctime>
#include <filesystem>
#include <fstream>
#include <loguru.cpp>
#include <sstream>
#include <thread>
#include <time.h>
Expand Down Expand Up @@ -53,14 +54,14 @@ std::vector<URCLegGPS> parseGPSLegs(std::string filepath) {
// we assume that gps already has a fix
gpscoords_t gps = {lat, lon};
URCLegGPS leg = {left_post_id, right_post_id, gps};
log(LOG_INFO, "Got urc leg at lat=%f lon=%f\n", lat, lon);
LOG_F(INFO, "Got urc leg at lat=%f lon=%f", lat, lon);
urc_legs.push_back(leg);
}
}
log(LOG_INFO, "Got %d urc legs\n", urc_legs.size());
LOG_F(INFO, "Got %ld urc legs\n", urc_legs.size());

if (urc_legs.size() == 0) {
log(LOG_ERROR, "could not get URC legs\n");
LOG_F(ERROR, "could not get URC legs");
std::exit(EXIT_FAILURE);
}

Expand Down Expand Up @@ -94,32 +95,85 @@ void parseCommandLine(int argc, char** argv) {
"LOG_WARN, LOG_ERROR)")
.default_value(std::string("LOG_INFO"))
.action([](const std::string& value) {
std::unordered_map<std::string, int> allowed{{"LOG_TRACE", LOG_TRACE},
{"LOG_DEBUG", LOG_DEBUG},
{"LOG_INFO", LOG_INFO},
{"LOG_WARN", LOG_WARN},
{"LOG_ERROR", LOG_ERROR}};
std::unordered_map<std::string, int> allowed{
{"LOG_ERROR", loguru::Verbosity_ERROR},
{"LOG_WARN", loguru::Verbosity_WARNING},
{"LOG_INFO", loguru::Verbosity_INFO},
{"LOG_DEBUG", 2},
{"LOG_TRACE", 1},
};

if (allowed.find(value) != allowed.end()) {
setLogLevel(allowed[value]);
return value;
loguru::g_stderr_verbosity = allowed[value];
}

throw std::runtime_error("Invalid log level " + value);
});

program.add_argument("-nc", "--no-colors")
.help("disables colors in console logging")
.action([&](const auto&) { setColorsEnabled(false); })
.action([&](const auto&) { loguru::g_colorlogtostderr = false; })
.nargs(0);

try {
loguru::init(argc, argv);
namespace fs = std::filesystem;

const auto LOG_LIFESPAN = std::chrono::hours(24 * 7);
try {
for (const auto& entry : fs::directory_iterator(fs::current_path())) {
if (entry.path().extension() == ".log" && entry.path().stem() != "latest") {
// Format of dateString: YYYYMMDD_HHMMSS
std::string dateString = entry.path().stem();

// Extract components from the date string
int year, month, day, hour, minute, second;
int scan_count = sscanf(dateString.c_str(), "%4d%2d%2d_%2d%2d%2d", &year,
&month, &day, &hour, &minute, &second);

// Ensure scan output count is 6
CHECK_EQ_F(scan_count, 6);

// Create a tm structure
std::tm tm_struct = {};
tm_struct.tm_year = year - 1900;
tm_struct.tm_mon = month - 1;
tm_struct.tm_mday = day;
tm_struct.tm_hour = hour;
tm_struct.tm_min = minute;
tm_struct.tm_sec = second;

// Current time
std::time_t unixTime = std::mktime(&tm_struct);

// Calculate duration
auto duration = std::chrono::system_clock::now() -
std::chrono::system_clock::from_time_t(unixTime);

// Delete log if it's older than LOG_LIFESPAN
if (duration > LOG_LIFESPAN) {
fs::remove(entry.path());
}
}
}
} catch (const fs::filesystem_error& e) {
LOG_F(ERROR, "Error accessing current directory! %s", e.what());
}

const auto now = std::chrono::system_clock::now();
const std::time_t t_c = std::chrono::system_clock::to_time_t(now);
std::stringstream ss;
ss << std::put_time(std::localtime(&t_c), "%Y%m%d_%H%M%S.log");
std::string logFileName = ss.str();
loguru::add_file("latest.log", loguru::Truncate, loguru::Verbosity_INFO);
loguru::add_file(logFileName.c_str(), loguru::Append, loguru::Verbosity_INFO);

program.parse_args(argc, argv);
log(LOG_INFO,
"parseCommandLine got peripheral specified as: \"%s\", logLevel specified as: "
"\"%s\"\n",
program.get<std::string>("peripheral").c_str(),
program.get<std::string>("loglevel").c_str());
LOG_F(INFO,
"parseCommandLine got peripheral specified as: \"%s\", logLevel specified as: "
"\"%s\"",
program.get<std::string>("peripheral").c_str(),
program.get<std::string>("loglevel").c_str());
} catch (const std::runtime_error& err) {
std::cerr << err.what() << std::endl;
std::cerr << program;
Expand Down
4 changes: 2 additions & 2 deletions src/TunePID.cpp
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
#include "CAN/CAN.h"
#include "CAN/CANMotor.h"
#include "Constants.h"
#include "log.h"
#include "world_interface/real_world_constants.h"
#include "world_interface/world_interface.h"

Expand All @@ -23,7 +22,8 @@ using namespace robot::types;
using namespace std::chrono;
using namespace std::chrono_literals;

template <typename K, typename V> std::map<V, K> reverseMap(const std::map<K, V>& map) {
template <typename K, typename V>
std::map<V, K> reverseMap(const std::map<K, V>& map) {
std::map<V, K> reversed;
for (const auto& [k, v] : map) {
reversed.emplace(v, k);
Expand Down
12 changes: 6 additions & 6 deletions src/ar/MarkerPattern.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

#include <cassert>
#include <cstdint>
#include <loguru.hpp>
#include <memory>

#include <opencv2/core.hpp>
Expand All @@ -15,14 +16,13 @@ MarkerPattern::MarkerPattern(uint8_t data_region_size, uint8_t border_size, cv::
int id)
: data_region_size(data_region_size), border_size(border_size), id(id),
data_bits(cv::Ptr<cv::Mat>(new cv::Mat(bits))) {
assert(data_region_size > 0);
assert(border_size > 0);
assert(bits.rows == data_region_size);
assert(bits.cols == data_region_size);
CHECK_GT_F(data_region_size, 0);
CHECK_GT_F(border_size, 0);
CHECK_EQ_F(bits.rows, data_region_size);
CHECK_EQ_F(bits.cols, data_region_size);
}

MarkerPattern::MarkerPattern() {
}
MarkerPattern::MarkerPattern() {}

bool MarkerPattern::empty() const {
return this->data_bits.empty();
Expand Down
10 changes: 5 additions & 5 deletions src/ar/MarkerSet.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "MarkerSet.h"

#include <loguru.hpp>
#include <memory>
#include <unordered_map>
#include <vector>
Expand All @@ -22,15 +23,15 @@ MarkerSet::MarkerSet(uint8_t data_region_size, uint8_t border_size, float physic

MarkerSet::MarkerSet(uint8_t data_region_size, uint8_t border_size, float physical_size,
ar_dict_ptr markerDictPtr) {
assert(markerDictPtr);
CHECK_NOTNULL_F(markerDictPtr);
init(data_region_size, border_size, physical_size, markerDictPtr);
}

void MarkerSet::init(uint8_t data_region_size, uint8_t border_size, float physical_size,
ar_dict_ptr markerDict) {
assert(data_region_size > 0);
assert(border_size > 0);
assert(physical_size > 0);
CHECK_GT_F(data_region_size, 0);
CHECK_GT_F(border_size, 0);
CHECK_GT_F(physical_size, 0);
this->data_region_size = data_region_size;
this->border_size = border_size;
this->physical_size = physical_size;
Expand Down Expand Up @@ -112,7 +113,6 @@ constexpr size_t ARUCO_BORDER_SIZE = 1;
/** The physical size (in mm) of an ARUco marker. */
constexpr float ARUCO_PHYS_SIZE = 0.15; // we don't know this yet, change later


/**
Constructs the URC marker set
*/
Expand Down
Loading

0 comments on commit a01aa7b

Please sign in to comment.