Skip to content

Commit

Permalink
fix lint & add camera vision config option
Browse files Browse the repository at this point in the history
  • Loading branch information
Tyler-Lentz committed Jun 10, 2024
1 parent 977243d commit 94cf080
Show file tree
Hide file tree
Showing 7 changed files with 65 additions and 34 deletions.
1 change: 1 addition & 0 deletions configs/config.json
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
},
"coverage": {
"altitude_m": 30.0,
"camera_vision_m": 20,
"method": "hover",
"hover": {
"pictures_per_stop": 1,
Expand Down
1 change: 1 addition & 0 deletions configs/dev-config.json
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
},
"coverage": {
"altitude_m": 30.0,
"camera_vision_m": 20,
"method": "hover",
"hover": {
"pictures_per_stop": 1,
Expand Down
19 changes: 11 additions & 8 deletions include/pathing/static.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,14 +197,17 @@ class RRT {
*/
class ForwardCoveragePathing {
public:
ForwardCoveragePathing(const RRTPoint &start, double scan_radius, Polygon bounds, Polygon airdrop_zone,
std::vector<Polygon> obstacles = {},
AirdropCoverageConfig config = {.altitude_m = 30.0,
.method = AirdropCoverageMethod::Enum::FORWARD,
.hover = {},
.forward = {.optimize = false,
.vertical = false,
.one_way = false}});
ForwardCoveragePathing(const RRTPoint &start,
double scan_radius,
Polygon bounds,
Polygon airdrop_zone,
std::vector<Polygon> obstacles = {},
AirdropCoverageConfig config = {.altitude_m = 30.0,
.method = AirdropCoverageMethod::Enum::FORWARD,
.hover = {},
.forward = {.optimize = false,
.vertical = false,
.one_way = false}});

/**
* Generates a path of parallel lines to cover a given area
Expand Down
12 changes: 8 additions & 4 deletions include/utilities/obc_config.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,15 @@

#include <variant>
#include <string>
#include <utility>
#include <unordered_set>
#include <initializer_list>
#include "udp_squared/internal/enum.h"
#include "utilities/constants.hpp"
#include "utilities/datatypes.hpp"

#define CONFIG_VARIANT_MAPPING_T(enum_type) const std::initializer_list<std::pair<std::string, enum_type>>
#define CONFIG_VARIANT_MAPPING_T(enum_type) \
const std::initializer_list<std::pair<std::string, enum_type>>

struct LoggingConfig {
std::string dir;
Expand Down Expand Up @@ -43,7 +46,7 @@ namespace PointFetchMethod {
CONFIG_VARIANT_MAPPING_T(Enum) MAPPINGS = {
{"none", Enum::NONE}, {"random", Enum::RANDOM}, {"nearest", Enum::NEAREST}
};
};
}; // namespace PointFetchMethod

struct RRTConfig {
int iterations_per_waypoint; // number of iterations run between two waypoints
Expand All @@ -62,14 +65,15 @@ namespace AirdropCoverageMethod {
CONFIG_VARIANT_MAPPING_T(Enum) MAPPINGS = {
{"hover", Enum::HOVER}, {"forward", Enum::FORWARD}
};
};
}; // namespace AirdropCoverageMethod

struct AirdropCoverageConfig {
double altitude_m;
double camera_vision_m;
AirdropCoverageMethod::Enum method;
struct {
std::size_t pictures_per_stop;
std::time_t hover_time_s;
std::time_t hover_time_s;
} hover;
struct {
bool optimize; // whether to ignore the config below and run all ways.
Expand Down
18 changes: 10 additions & 8 deletions include/utilities/obc_config_macros.hpp
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
#ifndef INCLUDE_UTILITIES_OBC_CONFIG_MACROS_HPP_
#define INCLUDE_UTILITIES_OBC_CONFIG_MACROS_HPP_

#include <string>

/*
( ) /\ _ (
\ | ( \ ( \.( ) _____
Expand All @@ -27,7 +29,8 @@
// just use these macros to do the parsing for the config
// it saves like 5 characters, and forces you to use .at instead of [] to index into the json
// because .at gives more descriptive error messages
// ALSO: does some shenanegans with tracking the line number of the last call to PARSE and handling errors
// ALSO: does some shenanegans with tracking the line number of the
// last call to PARSE and handling errors

// return statement in this macro in catch case is there to supress compiler warning b/c
// it doesn't know that FATAL log will kill it
Expand All @@ -39,8 +42,8 @@
return nlohmann::json(); \
}

// basically setting up an overloaded macro where you can pass in a variable number of args with the same
// macro name. Same setup as in the gcs macros
// basically setting up an overloaded macro where you can pass in a variable number of args
// with the same macro name. Same setup as in the gcs macros
#define GET_MACRO_5(_1, _2, _3, _4, _5, NAME, ...) NAME
#define PARSE_CONFIG_2(p1, p2) configs.at(#p1).at(#p2)
#define PARSE_CONFIG_3(p1, p2, p3) configs.at(#p1).at(#p2).at(#p3)
Expand All @@ -54,9 +57,8 @@
#define PARSE(...) \
[configs]() { \
HANDLE_JSON_EXCEPTION( \
GET_MACRO_5(__VA_ARGS__, PARSE_CONFIG_5, PARSE_CONFIG_4, PARSE_CONFIG_3, PARSE_CONFIG_2) \
(__VA_ARGS__) \
) \
GET_MACRO_5(__VA_ARGS__, PARSE_CONFIG_5, PARSE_CONFIG_4, \
PARSE_CONFIG_3, PARSE_CONFIG_2) (__VA_ARGS__)) \
}()

// look in the code below for an example on how to use this function
Expand All @@ -70,7 +72,7 @@ constexpr T PARSE_VARIANT(CONFIG_VARIANT_MAPPING_T(T) mapping, std::string input
}
}
LOG_F(FATAL, "Unknown config option %s", input.c_str());
std::exit(1); // not needed except so the compiler knows this cannot reach end of function
std::exit(1); // not needed except so the compiler knows this cannot reach end of function
}

// and then at the very end we prevent having to duplicate typing
Expand Down Expand Up @@ -101,4 +103,4 @@ constexpr T PARSE_VARIANT(CONFIG_VARIANT_MAPPING_T(T) mapping, std::string input
GET_MACRO_5(__VA_ARGS__, SET_CONFIG_OPT_5_VARIANT, SET_CONFIG_OPT_4_VARIANT, \
SET_CONFIG_OPT_3_VARIANT, SET_CONFIG_OPT_2_VARIANT) (mapping::MAPPINGS, __VA_ARGS__)

#endif // INCLUDE_UTILITIES_OBC_CONFIG_MACROS_HPP_
#endif // INCLUDE_UTILITIES_OBC_CONFIG_MACROS_HPP_
45 changes: 32 additions & 13 deletions src/pathing/static.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,14 +281,13 @@ RRTNode *RRT::parseOptions(const std::vector<std::pair<RRTNode *, RRTOption>> &o

void RRT::optimizeTree(RRTNode *sample) { tree.RRTStar(sample, rewire_radius); }

ForwardCoveragePathing::ForwardCoveragePathing(const RRTPoint &start, double scan_radius, Polygon bounds,
Polygon airdrop_zone, std::vector<Polygon> obstacles,
AirdropCoverageConfig config)
: start(start),
scan_radius(scan_radius),
airspace(Environment(bounds, airdrop_zone, {}, obstacles)),
dubins(Dubins(TURNING_RADIUS, POINT_SEPARATION)),
config(config) {}
ForwardCoveragePathing::ForwardCoveragePathing(
const RRTPoint &start, double scan_radius, Polygon bounds,
Polygon airdrop_zone, std::vector<Polygon> obstacles,
AirdropCoverageConfig config):
start(start), scan_radius(scan_radius),
airspace(Environment(bounds, airdrop_zone, {}, obstacles)),
dubins(Dubins(TURNING_RADIUS, POINT_SEPARATION)), config(config) {}

std::vector<XYZCoord> ForwardCoveragePathing::run() const {
return config.forward.optimize ? coverageOptimal() : coverageDefault();
Expand Down Expand Up @@ -362,8 +361,9 @@ std::vector<XYZCoord> ForwardCoveragePathing::coverageOptimal() const {
return generatePath(dubins_paths[best_path_idx], waypoints);
}

std::vector<XYZCoord> ForwardCoveragePathing::generatePath(const std::vector<RRTOption> &dubins_options,
const std::vector<RRTPoint> &waypoints) const {
std::vector<XYZCoord> ForwardCoveragePathing::generatePath(
const std::vector<RRTOption> &dubins_options,
const std::vector<RRTPoint> &waypoints) const {
std::vector<XYZCoord> path;

// height adjustement
Expand Down Expand Up @@ -398,6 +398,14 @@ std::vector<XYZCoord> ForwardCoveragePathing::generatePath(const std::vector<RRT
return path;
}

HoverCoveragePathing::HoverCoveragePathing(Polygon flight_bounds, Polygon drop_zone):
flight_bounds{flight_bounds}, drop_zone{drop_zone}
{}

std::vector<XYZCoord> HoverCoveragePathing::run() {
return {};
}

AirdropApproachPathing::AirdropApproachPathing(const RRTPoint &start, const XYZCoord &goal,
RRTPoint wind, Polygon bounds,
std::vector<Polygon> obstacles,
Expand Down Expand Up @@ -475,12 +483,23 @@ std::vector<GPSCoord> generateInitialPath(std::shared_ptr<MissionState> state) {
int count = 0;

for (XYZCoord wpt : path) {
output_coords.push_back(state->getCartesianConverter().value().toLatLng(wpt));
output_coords.push_back(state->getCartesianConverter()->toLatLng(wpt));
}

return output_coords;
}

std::vector<GPSCoord> generateSearchPath(std::shared_ptr<MissionState> state) {
return {};
}
if (state->config.pathing.coverage.method == AirdropCoverageMethod::Enum::FORWARD) {
LOG_F(FATAL, "Forward search path not fully integrated yet.");
return {};
} else { // hover
const auto& [flight_bounds, airdrop_bounds, _, __] = state->mission_params.getConfig();
HoverCoveragePathing pathing(flight_bounds, airdrop_bounds);
std::vector<GPSCoord> coords;
for (const XYZCoord& coord : pathing.run()) {
coords.push_back(state->getCartesianConverter()->toLatLng(coord));
}
return coords;
}
}
3 changes: 2 additions & 1 deletion src/utilities/obc_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@ OBCConfig::OBCConfig(int argc, char* argv[]) {
SET_CONFIG_OPT_VARIANT(AirdropCoverageMethod, pathing, coverage, method);

SET_CONFIG_OPT(pathing, coverage, altitude_m);
SET_CONFIG_OPT(pathing, coverage, camera_vision_m);
SET_CONFIG_OPT(pathing, coverage, hover, hover_time_s);
SET_CONFIG_OPT(pathing, coverage, hover, pictures_per_stop);
SET_CONFIG_OPT(pathing, coverage, forward, optimize);
Expand Down Expand Up @@ -81,7 +82,7 @@ OBCConfig::OBCConfig(int argc, char* argv[]) {
SET_CONFIG_OPT(camera, lucid, device_link_throughput_limit);

SET_CONFIG_OPT(camera, lucid, gamma_enable);
SET_CONFIG_OPT(camera, lucid, gamma); // bruh
SET_CONFIG_OPT(camera, lucid, gamma); // bruh
SET_CONFIG_OPT(camera, lucid, gain_auto);
SET_CONFIG_OPT(camera, lucid, gain_auto_upper_limit);
SET_CONFIG_OPT(camera, lucid, gain_auto_lower_limit);
Expand Down

0 comments on commit 94cf080

Please sign in to comment.