Autonomy Software C++ 24.5.1
Welcome to the Autonomy Software repository of the Mars Rover Design Team (MRDT) at Missouri University of Science and Technology (Missouri S&T)! API reference contains the source code and other resources for the development of the autonomy software for our Mars rover. The Autonomy Software project aims to compete in the University Rover Challenge (URC) by demonstrating advanced autonomous capabilities and robust navigation algorithms.
Loading...
Searching...
No Matches
AutonomyConstants.h
Go to the documentation of this file.
1
11#ifndef AUTONOMY_CONSTANTS_H
12#define AUTONOMY_CONSTANTS_H
13
16
18#include <opencv2/opencv.hpp>
19#include <quill/core/LogLevel.h>
20#include <sl/Camera.hpp>
21
23
24
32namespace constants
33{
37
38 // Sim mode constants.
39 extern const bool MODE_SIM;
40 extern const std::string SIM_IP_ADDRESS;
41 extern const uint SIM_WEBSOCKET_PORT;
42 extern const uint SIM_WEBRTC_QP;
43
44 // Safety constants.
45 extern const double BATTERY_MINIMUM_CELL_VOLTAGE;
46 extern const bool BATTERY_CHECKS_ENABLED;
47
48 // Logging constants.
49 extern const std::string LOGGING_OUTPUT_PATH_ABSOLUTE;
50 extern const quill::LogLevel CONSOLE_MIN_LEVEL;
51 extern const quill::LogLevel FILE_MIN_LEVEL;
52 extern const quill::LogLevel ROVECOMM_MIN_LEVEL;
53 extern const quill::LogLevel CONSOLE_DEFAULT_LEVEL;
54 extern const quill::LogLevel FILE_DEFAULT_LEVEL;
55 extern const quill::LogLevel ROVECOMM_DEFAULT_LEVEL;
56
57 // Logging color constants.
58 extern const std::string szTraceL3Color;
59 extern const std::string szTraceL2Color;
60 extern const std::string szTraceL1Color;
61 extern const std::string szDebugColor;
62 extern const std::string szInfoColor;
63 extern const std::string szNoticeColor;
64 extern const std::string szWarningColor;
65 extern const std::string szErrorColor;
66 extern const std::string szCriticalColor;
67 extern const std::string szBacktraceColor;
68
69 // RoveComm constants.
70 extern const int ROVECOMM_OUTGOING_UDP_PORT;
71 extern const int ROVECOMM_OUTGOING_TCP_PORT;
72 extern const std::string ROVECOMM_TCP_INTERFACE_IP;
74
78
79 // Power constants.
80 extern const float DRIVE_MAX_POWER;
81 extern const float DRIVE_MIN_POWER;
82 extern const float DRIVE_MAX_SAFE_POWER;
83
84 // Control constants.
85 extern const double DRIVE_PID_PROPORTIONAL;
86 extern const double DRIVE_PID_INTEGRAL;
87 extern const double DRIVE_PID_DERIVATIVE;
88 extern const double DRIVE_PID_FEEDFORWARD;
89 extern const double DRIVE_PID_MAX_ERROR;
90 extern const double DRIVE_PID_MAX_INTEGRAL_TERM;
91 extern const double DRIVE_PID_MAX_RAMP_RATE;
92 extern const double DRIVE_PID_OUTPUT_FILTER;
93 extern const double DRIVE_PID_TOLERANCE;
94 extern const bool DRIVE_PID_OUTPUT_REVERSED;
95 extern const bool DRIVE_SQUARE_CONTROL_INPUTS;
96 extern const bool DRIVE_CURVATURE_KINEMATICS_ALLOW_TURN_WHILE_STOPPED;
98
102
103 // Recording adjustments.
104 extern const int RECORDER_FPS;
105 // Camera recording toggles.
106 extern const bool ZED_MAINCAM_ENABLE_RECORDING;
107 extern const bool BASICCAM_GROUNDCAM_ENABLE_RECORDING;
108 // TagDetector recording toggles.
109 extern const bool TAGDETECT_MAINCAM_ENABLE_RECORDING;
110 extern const bool TAGDETECT_GROUNDCAM_ENABLE_RECORDING;
111 // ObjectDetector recording toggles.
112 extern const bool OBJECTDETECT_MAINCAM_ENABLE_RECORDING;
114
118
119 // ZedCam Basic Config.
120 extern const sl::RESOLUTION ZED_BASE_RESOLUTION;
121 extern const sl::UNIT ZED_MEASURE_UNITS;
122 extern const sl::COORDINATE_SYSTEM ZED_COORD_SYSTEM;
123 extern const sl::DEPTH_MODE ZED_DEPTH_MODE;
124 extern const sl::VIEW ZED_RETRIEVE_VIEW;
125 extern const bool ZED_SDK_VERBOSE;
126 extern const bool ZED_SENSING_FILL;
127 extern const float ZED_DEFAULT_MINIMUM_DISTANCE;
128 extern const float ZED_DEFAULT_MAXIMUM_DISTANCE;
129 extern const float ZED_DEFAULT_FLOOR_PLANE_ERROR;
130 extern const int ZED_DEPTH_STABILIZATION;
131 // ZedCam SVO Recording Config.
132 extern const sl::SVO_COMPRESSION_MODE ZED_SVO_COMPRESSION;
133 extern const int ZED_SVO_BITRATE;
134 // ZedCam Positional Tracking Config.
135 extern const sl::POSITIONAL_TRACKING_MODE ZED_POSETRACK_MODE;
136 extern const bool ZED_POSETRACK_AREA_MEMORY;
137 extern const bool ZED_POSETRACK_POSE_SMOOTHING;
138 extern const bool ZED_POSETRACK_FLOOR_IS_ORIGIN;
139 extern const bool ZED_POSETRACK_ENABLE_IMU_FUSION;
140 extern const float ZED_POSETRACK_USABLE_DEPTH_MIN;
141 extern const bool ZED_POSETRACK_USE_GRAVITY_ORIGIN;
142 // ZedCam Spatial Mapping Config.
143 extern const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE ZED_MAPPING_TYPE;
144 extern const float ZED_MAPPING_RANGE_METER;
145 extern const float ZED_MAPPING_RESOLUTION_METER;
146 extern const int ZED_MAPPING_MAX_MEMORY;
147 extern const bool ZED_MAPPING_USE_CHUNK_ONLY;
148 extern const int ZED_MAPPING_STABILITY_COUNTER;
149 // ZedCam Object Detection Config.
150 extern const bool ZED_OBJDETECTION_TRACK_OBJ;
151 extern const bool ZED_OBJDETECTION_SEGMENTATION;
152 extern const sl::OBJECT_FILTERING_MODE ZED_OBJDETECTION_FILTERING;
153 extern const float ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT;
154 extern const float ZED_OBJDETECTION_BATCH_RETENTION_TIME;
155 extern const float ZED_OBJDETECTION_BATCH_LATENCY;
156 // Zed Fusion Config.
157 extern const sl::UNIT FUSION_MEASUREMENT_UNITS;
158 extern const sl::COORDINATE_SYSTEM FUSION_COORD_SYSTEM;
159 extern const bool FUSION_SDK_VERBOSE;
160 extern const bool FUSION_ENABLE_GNSS_FUSION;
161
162 // BasicCam Basic Config.
163 extern const cv::InterpolationFlags BASICCAM_RESIZE_INTERPOLATION_METHOD;
165
169
170 // Main ZED Camera.
171 extern const int ZED_MAINCAM_RESOLUTIONX;
172 extern const int ZED_MAINCAM_RESOLUTIONY;
173 extern const int ZED_MAINCAM_FPS;
174 extern const int ZED_MAINCAM_HORIZONTAL_FOV;
175 extern const int ZED_MAINCAM_VERTICAL_FOV;
176 extern const bool ZED_MAINCAM_EXPORT_SVO_RECORDING;
177 extern const bool ZED_MAINCAM_EXPORT_SPATIAL_MAP;
178 extern const bool ZED_MAINCAM_USE_GPU_MAT;
179 extern const bool ZED_MAINCAM_USE_HALF_PRECISION_DEPTH;
180 extern const bool ZED_MAINCAM_FUSION_MASTER;
181 extern const int ZED_MAINCAM_FRAME_RETRIEVAL_THREADS;
182 extern const int ZED_MAINCAM_SERIAL;
183
184 // Ground Basic Cam.
185 extern const int BASICCAM_GROUNDCAM_RESOLUTIONX;
186 extern const int BASICCAM_GROUNDCAM_RESOLUTIONY;
187 extern const int BASICCAM_GROUNDCAM_FPS;
188 extern const int BASICCAM_GROUNDCAM_HORIZONTAL_FOV;
189 extern const int BASICCAM_GROUNDCAM_VERTICAL_FOV;
190 extern const int BASICCAM_GROUNDCAM_FRAME_RETRIEVAL_THREADS;
191 extern const int BASICCAM_GROUNDCAM_INDEX;
192 extern const PIXEL_FORMATS BASICCAM_GROUNDCAM_PIXELTYPE;
194
198
199 extern const double BBOX_MIN_LIFETIME_THRESHOLD;
200 extern const double BBOX_MIN_SCREEN_PERCENTAGE;
201 extern const double BBOX_TRACKER_LOST_TIMEOUT;
202 extern const double BBOX_TRACKER_MAX_TRACK_TIME;
203 extern const double BBOX_TRACKER_IOU_MATCH_THRESHOLD;
204 extern const tracking::TrackerType BBOX_TRACKER_TYPE;
205
207
211
212 // Main ZED Camera.
213 extern const int TAGDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
214 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_MAX_ITER;
215 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_METHOD;
216 extern const bool TAGDETECT_MAINCAM_DETECT_INVERTED_MARKER;
217 extern const int TAGDETECT_MAINCAM_MARKER_BORDER_BITS;
218 extern const bool TAGDETECT_MAINCAM_USE_ARUCO3_DETECTION;
219 extern const bool TAGDETECT_MAINCAM_ENABLE_TRACKING;
220 extern const int TAGDETECT_MAINCAM_MAX_FPS;
221 extern const bool TAGDETECT_MAINCAM_ENABLE_TORCH;
222 extern const std::string TAGDETECT_MAINCAM_TORCH_MODEL;
223 extern const float TAGDETECT_MAINCAM_TORCH_CONFIDENCE;
224 extern const float TAGDETECT_MAINCAM_TORCH_NMS_THRESH;
225
229
230 // Main ZED Camera.
231 extern const int OBJECTDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
232 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TRACKING;
233 extern const int OBJECTDETECT_MAINCAM_MAX_FPS;
234 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TORCH;
235 extern const std::string OBJECTDETECT_MAINCAM_TORCH_MODEL;
236 extern const float OBJECTDETECT_MAINCAM_TORCH_CONFIDENCE;
237 extern const float OBJECTDETECT_MAINCAM_TORCH_NMS_THRESH;
238
240
244
245 // LiDAR Data Handler.
246 extern const std::string LIDAR_HANDLER_DB_PATH; // The path to the LiDAR database file.
247
249
253
254 // Global GeoPlanner
255 extern const double GEOPLANNER_TILE_SIZE; // The size of each tile in the GeoPlanner.
256
258
262
263 // OpenCV ArUco detection config.
264 extern const cv::aruco::PredefinedDictionaryType ARUCO_DICTIONARY;
265 extern const float ARUCO_TAG_SIDE_LENGTH;
266 extern const double ARUCO_PIXEL_THRESHOLD;
267 extern const double ARUCO_PIXEL_THRESHOLD_MAX_VALUE;
268 extern const cv::Mat ARUCO_SHARPEN_KERNEL_FAST;
269 extern const cv::Mat ARUCO_SHARPEN_KERNEL_EXTRA;
270 extern const cv::Mat ARUCO_EDGE_KERNEL;
271
273
277
278 // Handler.
279 extern const int STATEMACHINE_MAX_IPS;
280 extern const double STATEMACHINE_ZED_REALIGN_THRESHOLD;
281
282 // Approaching Marker State
283 extern const double APPROACH_MARKER_MOTOR_POWER;
284 extern const double APPROACH_MARKER_PROXIMITY_THRESHOLD;
285 extern const double APPROACH_MARKER_LOST_GIVE_UP_TIME;
286 extern const bool APPROACH_MARKER_VERIFY_POSITION;
287 extern const double APPROACH_MARKER_VERIFY_TIME;
288 extern const double APPROACH_MARKER_TAG_LOST_BUFFER_TIME;
289 extern const bool APPROACH_MARKER_ENABLE_STUCK_DETECT;
290
291 // Approaching Object State
292 extern const double APPROACH_OBJECT_MOTOR_POWER;
293 extern const double APPROACH_OBJECT_PROXIMITY_THRESHOLD;
294 extern const double APPROACH_OBJECT_LOST_GIVE_UP_TIME;
295 extern const bool APPROACH_OBJECT_VERIFY_POSITION;
296 extern const double APPROACH_OBJECT_VERIFY_TIME;
297 extern const double APPROACH_OBJECT_LOST_BUFFER_TIME;
298 extern const bool APPROACH_OBJECT_ENABLE_STUCK_DETECT;
299
300 // Stuck State
301 extern const double STUCK_CHECK_INTERVAL;
302 extern const unsigned int STUCK_CHECK_ATTEMPTS;
303 extern const double STUCK_CHECK_ROT_THRESH;
304 extern const double STUCK_CHECK_VEL_THRESH;
305 extern const double STUCK_SAME_POINT_PROXIMITY;
306 extern const double STUCK_HEADING_ALIGN_TIMEOUT;
307 extern const double STUCK_ALIGN_DEGREES;
308 extern const double STUCK_ALIGN_TOLERANCE;
309
310 // Reverse State.
311 extern const double REVERSE_MOTOR_POWER;
312 extern const double REVERSE_DISTANCE;
313 extern const double REVERSE_TIMEOUT_PER_METER;
314 extern const bool REVERSE_MAINTAIN_HEADING;
315
316 // Search Pattern State
317 extern const double SEARCH_MOTOR_POWER;
318 extern const double SEARCH_ANGULAR_STEP_DEGREES;
319 extern const double SEARCH_SPIRAL_SPACING;
320 extern const double SEARCH_ZIGZAG_SPACING;
321 extern const double SEARCH_SNAKE_SLITHERS;
322 extern const double SEARCH_WAYPOINT_PROXIMITY;
323 extern const bool SEARCH_ENABLE_STUCK_DETECT;
324
325 // Navigating State.
326 extern const double NAVIGATING_MOTOR_POWER;
327 extern const double NAVIGATING_REACHED_GOAL_RADIUS;
328 extern const bool NAVIGATING_VERIFY_POSITION;
329 extern const double NAVIGATING_VERIFY_SAMPLE_TIME;
330 extern const bool NAVIGATING_ENABLE_STUCK_DETECT;
331
332 // Avoidance State.
333 extern const double AVOIDANCE_STATE_MOTOR_POWER;
334
336
340
341 // Stanley Controller config.
342 extern const double STANLEY_CROSSTRACK_CONTROL_GAIN;
343 extern const double STANLEY_WHEELBASE;
344 extern const double STANLEY_ANGULAR_VELOCITY_LIMIT;
345 extern const int STANLEY_PREDICTION_HORIZON;
346 extern const double STANLEY_PREDICTION_TIME_STEP;
347
348 // ASTAR config.
349 extern const double ASTAR_AVOIDANCE_MULTIPLIER;
350 extern const double ASTAR_MAX_SEARCH_GRID;
351 extern const double ASTAR_MAX_SEARCH_TIME;
352 extern const double ASTAR_NODE_SIZE;
353
355
359
360 // NavBoard.
361 extern const double NAVBOARD_MAX_GPS_DATA_AGE;
362 extern const double NAVBOARD_MAX_COMPASS_DATA_AGE;
363
365
366} // namespace constants
367
368#endif // AUTONOMY_CONSTANTS_H
Header file for the BoundingBoxTracking class, which is used to track bounding boxes in images using ...
Defines the Camera base interface class.
uint32_t uint
InterpolationFlags
PredefinedDictionaryType
Namespace containing all constants for autonomy software. Including AutonomyGlobals....
Definition AutonomyConstants.cpp:22