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;
83 extern const float DRIVE_MAX_EFFORT;
84 extern const float DRIVE_MIN_EFFORT;
87 extern const double DRIVE_PID_PROPORTIONAL;
88 extern const double DRIVE_PID_INTEGRAL;
89 extern const double DRIVE_PID_DERIVATIVE;
90 extern const double DRIVE_PID_FEEDFORWARD;
91 extern const double DRIVE_PID_MAX_ERROR;
92 extern const double DRIVE_PID_MAX_INTEGRAL_TERM;
93 extern const double DRIVE_PID_MAX_RAMP_RATE;
94 extern const double DRIVE_PID_OUTPUT_FILTER;
95 extern const double DRIVE_PID_TOLERANCE;
96 extern const bool DRIVE_PID_OUTPUT_REVERSED;
97 extern const bool DRIVE_SQUARE_CONTROL_INPUTS;
98 extern const bool DRIVE_CURVATURE_KINEMATICS_ALLOW_TURN_WHILE_STOPPED;
106 extern const int RECORDER_FPS;
108 extern const bool ZED_MAINCAM_ENABLE_RECORDING;
109 extern const bool BASICCAM_GROUNDCAM_ENABLE_RECORDING;
111 extern const bool TAGDETECT_MAINCAM_ENABLE_RECORDING;
112 extern const bool TAGDETECT_GROUNDCAM_ENABLE_RECORDING;
114 extern const bool OBJECTDETECT_MAINCAM_ENABLE_RECORDING;
122 extern const sl::RESOLUTION ZED_BASE_RESOLUTION;
123 extern const sl::UNIT ZED_MEASURE_UNITS;
124 extern const sl::COORDINATE_SYSTEM ZED_COORD_SYSTEM;
125 extern const sl::DEPTH_MODE ZED_DEPTH_MODE;
126 extern const sl::VIEW ZED_RETRIEVE_VIEW;
127 extern const bool ZED_SDK_VERBOSE;
128 extern const bool ZED_SENSING_FILL;
129 extern const float ZED_DEFAULT_MINIMUM_DISTANCE;
130 extern const float ZED_DEFAULT_MAXIMUM_DISTANCE;
131 extern const float ZED_DEFAULT_FLOOR_PLANE_ERROR;
132 extern const int ZED_DEPTH_STABILIZATION;
134 extern const sl::SVO_COMPRESSION_MODE ZED_SVO_COMPRESSION;
135 extern const int ZED_SVO_BITRATE;
137 extern const sl::POSITIONAL_TRACKING_MODE ZED_POSETRACK_MODE;
138 extern const bool ZED_POSETRACK_AREA_MEMORY;
139 extern const bool ZED_POSETRACK_POSE_SMOOTHING;
140 extern const bool ZED_POSETRACK_FLOOR_IS_ORIGIN;
141 extern const bool ZED_POSETRACK_ENABLE_IMU_FUSION;
142 extern const float ZED_POSETRACK_USABLE_DEPTH_MIN;
143 extern const bool ZED_POSETRACK_USE_GRAVITY_ORIGIN;
145 extern const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE ZED_MAPPING_TYPE;
146 extern const float ZED_MAPPING_RANGE_METER;
147 extern const float ZED_MAPPING_RESOLUTION_METER;
148 extern const int ZED_MAPPING_MAX_MEMORY;
149 extern const bool ZED_MAPPING_USE_CHUNK_ONLY;
150 extern const int ZED_MAPPING_STABILITY_COUNTER;
152 extern const bool ZED_OBJDETECTION_TRACK_OBJ;
153 extern const bool ZED_OBJDETECTION_SEGMENTATION;
154 extern const sl::OBJECT_FILTERING_MODE ZED_OBJDETECTION_FILTERING;
155 extern const float ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT;
156 extern const float ZED_OBJDETECTION_BATCH_RETENTION_TIME;
157 extern const float ZED_OBJDETECTION_BATCH_LATENCY;
159 extern const sl::UNIT FUSION_MEASUREMENT_UNITS;
160 extern const sl::COORDINATE_SYSTEM FUSION_COORD_SYSTEM;
161 extern const bool FUSION_SDK_VERBOSE;
162 extern const bool FUSION_ENABLE_GNSS_FUSION;
173 extern const int ZED_MAINCAM_RESOLUTIONX;
174 extern const int ZED_MAINCAM_RESOLUTIONY;
175 extern const int ZED_MAINCAM_FPS;
176 extern const int ZED_MAINCAM_HORIZONTAL_FOV;
177 extern const int ZED_MAINCAM_VERTICAL_FOV;
178 extern const bool ZED_MAINCAM_EXPORT_SVO_RECORDING;
179 extern const bool ZED_MAINCAM_EXPORT_SPATIAL_MAP;
180 extern const bool ZED_MAINCAM_USE_GPU_MAT;
181 extern const bool ZED_MAINCAM_USE_HALF_PRECISION_DEPTH;
182 extern const bool ZED_MAINCAM_FUSION_MASTER;
183 extern const int ZED_MAINCAM_FRAME_RETRIEVAL_THREADS;
184 extern const int ZED_MAINCAM_SERIAL;
187 extern const int BASICCAM_GROUNDCAM_RESOLUTIONX;
188 extern const int BASICCAM_GROUNDCAM_RESOLUTIONY;
189 extern const int BASICCAM_GROUNDCAM_FPS;
190 extern const int BASICCAM_GROUNDCAM_HORIZONTAL_FOV;
191 extern const int BASICCAM_GROUNDCAM_VERTICAL_FOV;
192 extern const int BASICCAM_GROUNDCAM_FRAME_RETRIEVAL_THREADS;
193 extern const int BASICCAM_GROUNDCAM_INDEX;
194 extern const PIXEL_FORMATS BASICCAM_GROUNDCAM_PIXELTYPE;
201 extern const double BBOX_MIN_LIFETIME_THRESHOLD;
202 extern const double BBOX_MIN_SCREEN_PERCENTAGE;
203 extern const double BBOX_TRACKER_LOST_TIMEOUT;
204 extern const double BBOX_TRACKER_MAX_TRACK_TIME;
205 extern const double BBOX_TRACKER_IOU_MATCH_THRESHOLD;
206 extern const tracking::TrackerType BBOX_TRACKER_TYPE;
215 extern const int TAGDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
216 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_MAX_ITER;
217 extern const int TAGDETECT_MAINCAM_CORNER_REFINE_METHOD;
218 extern const bool TAGDETECT_MAINCAM_DETECT_INVERTED_MARKER;
219 extern const int TAGDETECT_MAINCAM_MARKER_BORDER_BITS;
220 extern const bool TAGDETECT_MAINCAM_USE_ARUCO3_DETECTION;
221 extern const bool TAGDETECT_MAINCAM_ENABLE_TRACKING;
222 extern const int TAGDETECT_MAINCAM_MAX_FPS;
223 extern const bool TAGDETECT_MAINCAM_ENABLE_TORCH;
224 extern const std::string TAGDETECT_MAINCAM_TORCH_MODEL;
225 extern const float TAGDETECT_MAINCAM_TORCH_CONFIDENCE;
226 extern const float TAGDETECT_MAINCAM_TORCH_NMS_THRESH;
233 extern const int OBJECTDETECT_MAINCAM_DATA_RETRIEVAL_THREADS;
234 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TRACKING;
235 extern const int OBJECTDETECT_MAINCAM_MAX_FPS;
236 extern const bool OBJECTDETECT_MAINCAM_ENABLE_TORCH;
237 extern const std::string OBJECTDETECT_MAINCAM_TORCH_MODEL;
238 extern const float OBJECTDETECT_MAINCAM_TORCH_CONFIDENCE;
239 extern const float OBJECTDETECT_MAINCAM_TORCH_NMS_THRESH;
249 extern const float ARUCO_TAG_SIDE_LENGTH;
250 extern const double ARUCO_PIXEL_THRESHOLD;
251 extern const double ARUCO_PIXEL_THRESHOLD_MAX_VALUE;
252 extern const cv::Mat ARUCO_SHARPEN_KERNEL_FAST;
253 extern const cv::Mat ARUCO_SHARPEN_KERNEL_EXTRA;
254 extern const cv::Mat ARUCO_EDGE_KERNEL;
263 extern const int STATEMACHINE_MAX_IPS;
264 extern const double STATEMACHINE_ZED_REALIGN_THRESHOLD;
267 extern const double APPROACH_MARKER_MOTOR_POWER;
268 extern const double APPROACH_MARKER_PROXIMITY_THRESHOLD;
269 extern const double APPROACH_MARKER_LOST_GIVE_UP_TIME;
270 extern const bool APPROACH_MARKER_VERIFY_POSITION;
271 extern const double APPROACH_MARKER_VERIFY_TIME;
272 extern const double APPROACH_MARKER_TAG_LOST_BUFFER_TIME;
273 extern const bool APPROACH_MARKER_ENABLE_STUCK_DETECT;
276 extern const double APPROACH_OBJECT_MOTOR_POWER;
277 extern const double APPROACH_OBJECT_PROXIMITY_THRESHOLD;
278 extern const double APPROACH_OBJECT_LOST_GIVE_UP_TIME;
279 extern const bool APPROACH_OBJECT_VERIFY_POSITION;
280 extern const double APPROACH_OBJECT_VERIFY_TIME;
281 extern const double APPROACH_OBJECT_LOST_BUFFER_TIME;
282 extern const bool APPROACH_OBJECT_ENABLE_STUCK_DETECT;
285 extern const double STUCK_CHECK_INTERVAL;
286 extern const unsigned int STUCK_CHECK_ATTEMPTS;
287 extern const double STUCK_CHECK_ROT_THRESH;
288 extern const double STUCK_CHECK_VEL_THRESH;
289 extern const double STUCK_SAME_POINT_PROXIMITY;
290 extern const double STUCK_HEADING_ALIGN_TIMEOUT;
291 extern const double STUCK_ALIGN_DEGREES;
292 extern const double STUCK_ALIGN_TOLERANCE;
295 extern const double REVERSE_MOTOR_POWER;
296 extern const double REVERSE_DISTANCE;
297 extern const double REVERSE_TIMEOUT_PER_METER;
298 extern const bool REVERSE_MAINTAIN_HEADING;
301 extern const double SEARCH_MOTOR_POWER;
302 extern const double SEARCH_ANGULAR_STEP_DEGREES;
303 extern const double SEARCH_SPIRAL_SPACING;
304 extern const double SEARCH_ZIGZAG_SPACING;
305 extern const double SEARCH_SNAKE_SLITHERS;
306 extern const double SEARCH_WAYPOINT_PROXIMITY;
307 extern const bool SEARCH_ENABLE_STUCK_DETECT;
310 extern const double NAVIGATING_MOTOR_POWER;
311 extern const double NAVIGATING_REACHED_GOAL_RADIUS;
312 extern const bool NAVIGATING_VERIFY_POSITION;
313 extern const double NAVIGATING_VERIFY_SAMPLE_TIME;
314 extern const bool NAVIGATING_ENABLE_STUCK_DETECT;
317 extern const double AVOIDANCE_STATE_MOTOR_POWER;
334 extern const double STANLEY_CROSSTRACK_CONTROL_GAIN;
335 extern const double STANLEY_DIST_TO_FRONT_AXLE;
336 extern const double STANLEY_STEERING_ANGLE_LIMIT;
337 extern const int STANLEY_PREDICTION_HORIZON;
338 extern const double STANLEY_PREDICTION_TIME_STEP;
341 extern const double ASTAR_AVOIDANCE_MULTIPLIER;
342 extern const double ASTAR_MAX_SEARCH_GRID;
343 extern const double ASTAR_MAX_SEARCH_TIME;
344 extern const double ASTAR_NODE_SIZE;
353 extern const double NAVBOARD_MAX_GPS_DATA_AGE;
354 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