Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
17 changes: 17 additions & 0 deletions .clang-format
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
BasedOnStyle: Google
UseTab: Never
IndentWidth: 4
TabWidth: 4
ColumnLimit: 100
AccessModifierOffset: -3
IncludeBlocks: Regroup
SortIncludes: true
IncludeCategories:
- Regex: "^[^\"]*interface\\.(h|hpp)$"
Priority: 1
- Regex: "^<[^/]+\\.h>$"
Priority: 2
- Regex: "^<[a-zA-Z0-9_]+>$"
Priority: 3
- Regex: ".*"
Priority: 4
5 changes: 3 additions & 2 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -19,14 +19,15 @@
"customizations": {
"vscode": {
"settings": {
// Use bash instead ofk sh
// Use bash instead of sh
"terminal.integrated.defaultProfile.linux": "bash"
},
"extensions": [
"ms-vscode.cpptools",
"twxs.cmake",
"me-dutour-mathieu.vscode-github-actions"
]
],
"C_Cpp.clang_format_style": "file"
}
}

Expand Down
14 changes: 7 additions & 7 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,13 +44,13 @@ SET(CMAKE_C_FLAGS "-D_GNU_SOURCE")
# eight_jobs requires more than 12GB RAM
# sixteen_jobs requires more than 16GB RAM (I don't know how much, since I only have 16GB)
# Therefore we default to 4 jobs, so it doesn't crash anyone's laptop with 12GB ram.
if (NOT DEFINED CMAKE_JOB_POOLS)
set_property(GLOBAL PROPERTY JOB_POOLS j=4)
else()
message("Using user defined number of pools: ${CMAKE_JOB_POOLS}")
endif()
set(CMAKE_JOB_POOL_COMPILE j)
set(CMAKE_JOB_POOL_LINK j)
# if (NOT DEFINED CMAKE_JOB_POOLS)
# set_property(GLOBAL PROPERTY JOB_POOLS j=4)
# else()
# message("Using user defined number of pools: ${CMAKE_JOB_POOLS}")
# endif()
# set(CMAKE_JOB_POOL_COMPILE j)
# set(CMAKE_JOB_POOL_LINK j)

project(obcpp VERSION 1.0)

Expand Down
285 changes: 194 additions & 91 deletions README.md

Large diffs are not rendered by default.

3 changes: 2 additions & 1 deletion deps/opencv/opencv.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@ function(target_add_opencv target_name)
# Use system OpenCV installation from PATH
find_package(OpenCV REQUIRED)

include_directories(${OpenCV_INCLUDE_DIRS})
# Mark OpenCV headers as SYSTEM to suppress warnings from external library
include_directories(SYSTEM ${OpenCV_INCLUDE_DIRS})
target_link_libraries(${target_name} PRIVATE ${OpenCV_LIBS})
endfunction()
4 changes: 3 additions & 1 deletion src/camera/interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,9 @@ bool ImageData::saveToFile(std::string directory) const {
std::filesystem::path json_filepath =
save_dir / (std::to_string(this->TIMESTAMP) + std::string(".json"));

LOG_F(INFO, "Saving %s to %s", img_filepath, json_filepath);
LOG_F(INFO, "Saving %s to %s",
img_filepath.string().c_str(),
json_filepath.string().c_str());
saveImageToFile(this->DATA, img_filepath);
if (this->TELEMETRY.has_value()) {
saveImageTelemetryToFile(this->TELEMETRY.value(), json_filepath);
Expand Down
7 changes: 4 additions & 3 deletions src/network/gcs_routes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -265,8 +265,9 @@ DEF_GCS_HANDLE(Get, camera, capture) {
compressed_image = cv::imdecode(compressed_data, cv::IMREAD_COLOR);

if (!compressed_image.empty()) {
LOG_F(INFO,
"Compressed manual capture image from %d bytes to %d bytes (%.1f%% compression)",
LOG_F(INFO,
"Compressed manual capture image from %zu bytes to %zu bytes "
"(%.1f%% compression)",
image->DATA.total() * image->DATA.elemSize(), compressed_data.size(),
(1.0 - static_cast<double>(compressed_data.size()) /
(image->DATA.total() * image->DATA.elemSize())) *
Expand Down Expand Up @@ -393,7 +394,7 @@ DEF_GCS_HANDLE(Get, targets, all) {
compressed_image = cv::imdecode(compressed_data, cv::IMREAD_COLOR);

if (!compressed_image.empty()) {
LOG_F(INFO, "Compressed image from %d bytes to %d bytes (%.1f%% compression)",
LOG_F(INFO, "Compressed image from %zu bytes to %zu bytes (%.1f%% compression)",
run.annotatedImage.total() * run.annotatedImage.elemSize(),
compressed_data.size(),
(1.0 - static_cast<double>(compressed_data.size()) /
Expand Down
9 changes: 4 additions & 5 deletions src/network/mavlink.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -174,16 +174,15 @@ MavlinkClient::MavlinkClient(OBCConfig config)
});

this->passthrough->subscribe_message(WIND_COV, [this](const mavlink_message_t& message) {
auto payload = message.payload64;
// LOG_F(INFO, "UNIX TIME: %lu", payload[0]);
// LOG_F(INFO, "UNIX TIME: %lu", message.payload64[0]);

/*
NOT TESTED - don't actually know where the data is in thie uint64_t[]
TODO - test on actual pixhawk to make sure that the data makes sense
*/
this->data.wind.x = (payload[1] >> 56) & 0xFF;
this->data.wind.y = (payload[1] >> 48) & 0xFF;
this->data.wind.z = (payload[1] >> 40) & 0xFF;
this->data.wind.x = (message.payload64[1] >> 56) & 0xFF;
this->data.wind.y = (message.payload64[1] >> 48) & 0xFF;
this->data.wind.z = (message.payload64[1] >> 40) & 0xFF;
});
// this->telemetry->subscribe_attitude_euler(
// [this](mavsdk::Telemetry::EulerAngle attitude) {
Expand Down
4 changes: 2 additions & 2 deletions src/ticks/fly_search.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ void FlySearchTick::init() {
LOG_F(ERROR, "Failed to reset Mission");
}

LOG_F(INFO, "Total Waypoint #: %d", this->state->getMav()->totalWaypoints());
LOG_F(INFO, "Total Waypoint #: %zu", this->state->getMav()->totalWaypoints());
}

Tick* FlySearchTick::tick() {
Expand All @@ -64,7 +64,7 @@ Tick* FlySearchTick::tick() {
auto curr_waypoint = this->state->getMav()->curr_waypoint();

if (this->curr_mission_item != curr_waypoint) {
LOG_F(INFO, "FlySearch Area reached (%d, %d)", this->curr_mission_item, curr_waypoint);
LOG_F(INFO, "FlySearch Area reached (%zu, %d)", this->curr_mission_item, curr_waypoint);
for (int i = 0; i < this->state->config.pathing.coverage.hover.pictures_per_stop; i++) {
auto photo = this->state->getCamera()->takePicture(500ms, this->state->getMav());
if (state->config.camera.save_images_to_file) {
Expand Down
2 changes: 1 addition & 1 deletion tests/integration/airdrop_approach.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ int main() {

LOG_F(WARNING, "Running Approach");
std::vector<XYZCoord> path = approach.run();
LOG_F(INFO, "Path size: %d", path.size());
LOG_F(INFO, "Path size: %zu", path.size());

// files to put path_coordinates to
file.open("pathing_output/approach_coords.txt");
Expand Down
2 changes: 1 addition & 1 deletion tests/integration/coverage_pathing.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ int main() {
LOG_F(WARNING, "Running Search");
std::vector<XYZCoord> path = search.run();
LOG_F(INFO, "Search Complete");
LOG_F(INFO, "Path size: %d", path.size());
LOG_F(INFO, "Path size: %zu", path.size());

// files to put path_coordinates to
file.open("pathing_output/coverage_coords.txt");
Expand Down
2 changes: 1 addition & 1 deletion tests/integration/deviation_ranking.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ int main() {

// get the path, put it into the file
std::vector<XYZCoord> path = rrt.getPointsToGoal();
LOG_F(INFO, "Path size: %d", path.size());
LOG_F(INFO, "Path size: %zu", path.size());
LOG_F(INFO, "Path length: %f", path.size() * state->config.pathing.dubins.point_separation);

// files to put path_coordinates to
Expand Down
2 changes: 1 addition & 1 deletion tests/integration/path_planning.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ int main() {

// get the path, put it into the file
std::vector<XYZCoord> path = rrt.getPointsToGoal();
LOG_F(INFO, "Path size: %d", path.size());
LOG_F(INFO, "Path size: %zu", path.size());
LOG_F(INFO, "Path length: %f", path.size() * state->config.pathing.dubins.point_separation);

// files to put path_coordinates to
Expand Down