11#ifndef AUTONOMY_CONSTANTS_H
12#define AUTONOMY_CONSTANTS_H
18#include <opencv2/opencv.hpp>
19#include <quill/core/LogLevel.h>
20#include <sl/Camera.hpp>
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;
45 extern const double BATTERY_MINIMUM_CELL_VOLTAGE;
46 extern const bool BATTERY_CHECKS_ENABLED;
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;
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;
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;
80 extern const float DRIVE_MAX_POWER;
81 extern const float DRIVE_MIN_POWER;
82 extern const float DRIVE_MAX_SAFE_POWER;
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;
99 extern const float DRIVE_BOARD_MIN_SLOPE;
100 extern const float DRIVE_BOARD_MAX_SLOPE;
101 extern const float DRIVE_BOARD_MIN_DAMP;
102 extern const float DRIVE_BOARD_MAX_DAMP;
103 extern const float DRIVE_BOARD_ROLL_WEIGHT;
104 extern const float DRIVE_BOARD_PITCH_WEIGHT;
105 extern const float DRIVE_BOARD_YAW_WEIGHT;
113 extern const int RECORDER_FPS;
115 extern const bool ZED_MAINCAM_ENABLE_RECORDING;
116 extern const bool BASICCAM_GROUNDCAM_ENABLE_RECORDING;
118 extern const bool TAGDETECT_MAINCAM_ENABLE_RECORDING;
119 extern const bool TAGDETECT_GROUNDCAM_ENABLE_RECORDING;
121 extern const bool OBJECTDETECT_MAINCAM_ENABLE_RECORDING;
129 extern const sl::RESOLUTION ZED_BASE_RESOLUTION;
130 extern const sl::UNIT ZED_MEASURE_UNITS;
131 extern const sl::COORDINATE_SYSTEM ZED_COORD_SYSTEM;
132 extern const sl::DEPTH_MODE ZED_DEPTH_MODE;
133 extern const sl::VIEW ZED_RETRIEVE_VIEW;
134 extern const bool ZED_SDK_VERBOSE;
135 extern const bool ZED_SENSING_FILL;
136 extern const float ZED_DEFAULT_MINIMUM_DISTANCE;
137 extern const float ZED_DEFAULT_MAXIMUM_DISTANCE;
138 extern const float ZED_DEFAULT_FLOOR_PLANE_ERROR;
139 extern const int ZED_DEPTH_STABILIZATION;
141 extern const sl::SVO_COMPRESSION_MODE ZED_SVO_COMPRESSION;
142 extern const int ZED_SVO_BITRATE;
144 extern const sl::POSITIONAL_TRACKING_MODE ZED_POSETRACK_MODE;
145 extern const bool ZED_POSETRACK_AREA_MEMORY;
146 extern const bool ZED_POSETRACK_POSE_SMOOTHING;
147 extern const bool ZED_POSETRACK_FLOOR_IS_ORIGIN;
148 extern const bool ZED_POSETRACK_ENABLE_IMU_FUSION;
149 extern const float ZED_POSETRACK_USABLE_DEPTH_MIN;
150 extern const bool ZED_POSETRACK_USE_GRAVITY_ORIGIN;
152 extern const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE ZED_MAPPING_TYPE;
153 extern const float ZED_MAPPING_RANGE_METER;
154 extern const float ZED_MAPPING_RESOLUTION_METER;
155 extern const int ZED_MAPPING_MAX_MEMORY;
156 extern const bool ZED_MAPPING_USE_CHUNK_ONLY;
157 extern const int ZED_MAPPING_STABILITY_COUNTER;
159 extern const bool ZED_OBJDETECTION_TRACK_OBJ;
160 extern const bool ZED_OBJDETECTION_SEGMENTATION;
161 extern const sl::OBJECT_FILTERING_MODE ZED_OBJDETECTION_FILTERING;
162 extern const float ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT;
163 extern const float ZED_OBJDETECTION_BATCH_RETENTION_TIME;
164 extern const float ZED_OBJDETECTION_BATCH_LATENCY;
166 extern const sl::UNIT FUSION_MEASUREMENT_UNITS;
167 extern const sl::COORDINATE_SYSTEM FUSION_COORD_SYSTEM;
168 extern const bool FUSION_SDK_VERBOSE;
169 extern const bool FUSION_ENABLE_GNSS_FUSION;
180 extern const int ZED_MAINCAM_RESOLUTIONX;
181 extern const int ZED_MAINCAM_RESOLUTIONY;
182 extern const int ZED_MAINCAM_FPS;
183 extern const int ZED_MAINCAM_HORIZONTAL_FOV;
184 extern const int ZED_MAINCAM_VERTICAL_FOV;
185 extern const bool ZED_MAINCAM_EXPORT_SVO_RECORDING;
186 extern const bool ZED_MAINCAM_EXPORT_SPATIAL_MAP;
187 extern const bool ZED_MAINCAM_USE_GPU_MAT;
188 extern const bool ZED_MAINCAM_USE_HALF_PRECISION_DEPTH;
189 extern const bool ZED_MAINCAM_FUSION_MASTER;
190 extern const int ZED_MAINCAM_FRAME_RETRIEVAL_THREADS;
191 extern const int ZED_MAINCAM_SERIAL;
194 extern const int BASICCAM_GROUNDCAM_RESOLUTIONX;
195 extern const int BASICCAM_GROUNDCAM_RESOLUTIONY;
196 extern const int BASICCAM_GROUNDCAM_FPS;
197 extern const int BASICCAM_GROUNDCAM_HORIZONTAL_FOV;
198 extern const int BASICCAM_GROUNDCAM_VERTICAL_FOV;
199 extern const int BASICCAM_GROUNDCAM_FRAME_RETRIEVAL_THREADS;
200 extern const int BASICCAM_GROUNDCAM_INDEX;
201 extern const PIXEL_FORMATS BASICCAM_GROUNDCAM_PIXELTYPE;
208 extern const double BBOX_MIN_LIFETIME_THRESHOLD;
209 extern const double BBOX_MIN_SCREEN_PERCENTAGE;
210 extern const double BBOX_TRACKER_LOST_TIMEOUT;
211 extern const double BBOX_TRACKER_MAX_TRACK_TIME;
212 extern const double BBOX_TRACKER_IOU_MATCH_THRESHOLD;
213 extern const tracking::TrackerType BBOX_TRACKER_TYPE;
222 extern const int TAGDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
223 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_MAX_ITER;
224 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_METHOD;
225 extern const bool TAGDETECT_MAINCAM_DETECT_INVERTED_MARKER;
226 extern const int TAGDETECT_MAINCAM_MARKER_BORDER_BITS;
227 extern const bool TAGDETECT_MAINCAM_USE_ARUCO3_DETECTION;
228 extern const bool TAGDETECT_MAINCAM_ENABLE_TRACKING;
229 extern const int TAGDETECT_MAINCAM_MAX_FPS;
230 extern const bool TAGDETECT_MAINCAM_ENABLE_TORCH;
231 extern const std::string TAGDETECT_MAINCAM_TORCH_MODEL;
232 extern const float TAGDETECT_MAINCAM_TORCH_CONFIDENCE;
233 extern const float TAGDETECT_MAINCAM_TORCH_NMS_THRESH;
240 extern const int OBJECTDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
241 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TRACKING;
242 extern const int OBJECTDETECT_MAINCAM_MAX_FPS;
243 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TORCH;
244 extern const std::string OBJECTDETECT_MAINCAM_TORCH_MODEL;
245 extern const float OBJECTDETECT_MAINCAM_TORCH_CONFIDENCE;
246 extern const float OBJECTDETECT_MAINCAM_TORCH_NMS_THRESH;
255 extern const std::string LIDAR_HANDLER_DB_PATH;
264 extern const int VISUALIZER_WEBSERVER_PORT;
265 extern const std::string VISUALIZER_THREEJS_PATH;
266 extern const std::string VISUALIZER_ORBITCONTROLS_PATH;
275 extern const double GEOPLANNER_TILE_SIZE;
285 extern const float ARUCO_TAG_SIDE_LENGTH;
286 extern const double ARUCO_PIXEL_THRESHOLD;
287 extern const double ARUCO_PIXEL_THRESHOLD_MAX_VALUE;
288 extern const cv::Mat ARUCO_SHARPEN_KERNEL_FAST;
289 extern const cv::Mat ARUCO_SHARPEN_KERNEL_EXTRA;
290 extern const cv::Mat ARUCO_EDGE_KERNEL;
299 extern const int STATEMACHINE_MAX_IPS;
300 extern const double STATEMACHINE_ZED_REALIGN_THRESHOLD;
303 extern const double APPROACH_MARKER_MOTOR_POWER;
304 extern const double APPROACH_MARKER_PROXIMITY_THRESHOLD;
305 extern const double APPROACH_MARKER_LOST_GIVE_UP_TIME;
306 extern const bool APPROACH_MARKER_VERIFY_POSITION;
307 extern const double APPROACH_MARKER_VERIFY_TIME;
308 extern const double APPROACH_MARKER_TAG_LOST_BUFFER_TIME;
309 extern const bool APPROACH_MARKER_ENABLE_STUCK_DETECT;
312 extern const double APPROACH_OBJECT_MOTOR_POWER;
313 extern const double APPROACH_OBJECT_PROXIMITY_THRESHOLD;
314 extern const double APPROACH_OBJECT_LOST_GIVE_UP_TIME;
315 extern const bool APPROACH_OBJECT_VERIFY_POSITION;
316 extern const double APPROACH_OBJECT_VERIFY_TIME;
317 extern const double APPROACH_OBJECT_LOST_BUFFER_TIME;
318 extern const bool APPROACH_OBJECT_ENABLE_STUCK_DETECT;
321 extern const double STUCK_CHECK_INTERVAL;
322 extern const unsigned int STUCK_CHECK_ATTEMPTS;
323 extern const double STUCK_CHECK_ROT_THRESH;
324 extern const double STUCK_CHECK_VEL_THRESH;
325 extern const double STUCK_SAME_POINT_PROXIMITY;
326 extern const double STUCK_HEADING_ALIGN_TIMEOUT;
327 extern const double STUCK_ALIGN_DEGREES;
328 extern const double STUCK_ALIGN_TOLERANCE;
331 extern const double REVERSE_MOTOR_POWER;
332 extern const double REVERSE_DISTANCE;
333 extern const double REVERSE_TIMEOUT_PER_METER;
334 extern const bool REVERSE_MAINTAIN_HEADING;
337 extern const double SEARCH_MOTOR_POWER;
338 extern const double SEARCH_ANGULAR_STEP_DEGREES;
339 extern const double SEARCH_SPIRAL_SPACING;
340 extern const double SEARCH_ZIGZAG_SPACING;
341 extern const double SEARCH_SNAKE_SLITHERS;
342 extern const double SEARCH_WAYPOINT_PROXIMITY;
343 extern const bool SEARCH_ENABLE_STUCK_DETECT;
346 extern const double NAVIGATING_MOTOR_POWER;
347 extern const double NAVIGATING_REACHED_GOAL_RADIUS;
348 extern const bool NAVIGATING_VERIFY_POSITION;
349 extern const double NAVIGATING_VERIFY_SAMPLE_TIME;
350 extern const bool NAVIGATING_ENABLE_STUCK_DETECT;
359 extern const double STANLEY_CROSSTRACK_CONTROL_GAIN;
360 extern const double STANLEY_WHEELBASE;
361 extern const double STANLEY_ANGULAR_VELOCITY_LIMIT;
362 extern const int STANLEY_PREDICTION_HORIZON;
363 extern const double STANLEY_PREDICTION_TIME_STEP;
366 extern const double ASTAR_AVOIDANCE_MULTIPLIER;
367 extern const double ASTAR_MAX_SEARCH_GRID;
368 extern const double ASTAR_MAX_SEARCH_TIME;
369 extern const double ASTAR_NODE_SIZE;
378 extern const double NAVBOARD_MAX_GPS_DATA_AGE;
379 extern const double NAVBOARD_MAX_COMPASS_DATA_AGE;
Header file for the BoundingBoxTracking class, which is used to track bounding boxes in images using ...
Defines the Camera base interface class.
Namespace containing all constants for autonomy software. Including AutonomyGlobals....
Definition AutonomyConstants.cpp:22