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
1
11#ifndef CONSTS_H
12#define CONSTS_H
13
15
17#include <opencv2/opencv.hpp>
18#include <quill/core/LogLevel.h>
19#include <sl/Camera.hpp>
20
22
23
31namespace constants
32{
36
37 // Sim mode constants.
38#if defined(__AUTONOMY_SIM_MODE__) && __AUTONOMY_SIM_MODE__ == 1
39 const bool MODE_SIM = true; // SIM MODE ENABLED: Toggle RoveComm and Cameras to use local data from the SIM.
40#else
41 const bool MODE_SIM = false; // REG MODE ENABLED: Toggle RoveComm and Cameras to use standard configuration.
42#endif
43 const std::string SIM_IP_ADDRESS = "192.168.69.29"; // The IP address to use for simulation mode.
44 const uint SIM_WEBRTC_QP = 25; // The QP value to use for WebRTC in simulation mode. 0-51, 0 is lossless. If too high for network, frames drop.
45
46 // Safety constants.
47 const double BATTERY_MINIMUM_CELL_VOLTAGE = 3.2; // The minimum cell voltage of the battery before autonomy will forcefully enter Idle state.
48 const bool BATTERY_CHECKS_ENABLED = false; // If autonomy should monitor PMS Currents and as a result have the ability to shutdown autonomy.
49
50 // Logging constants.
51 const std::string LOGGING_OUTPUT_PATH_ABSOLUTE = "../logs/"; // The absolute to write output logging and video files to.
52 const quill::LogLevel CONSOLE_MIN_LEVEL = quill::LogLevel::TraceL3; // The minimum logging level that is allowed to send to the console log stream.
53 const quill::LogLevel FILE_MIN_LEVEL = quill::LogLevel::TraceL3; // The minimum logging level that is allowed to send to the file log streams.
54 const quill::LogLevel ROVECOMM_MIN_LEVEL = quill::LogLevel::Info; // The minimum logging level that is allowed to send to the RoveComm log stream.
55 const quill::LogLevel CONSOLE_DEFAULT_LEVEL = quill::LogLevel::Info; // The default logging level for console stream.
56 const quill::LogLevel FILE_DEFAULT_LEVEL = quill::LogLevel::TraceL3; // The default logging level for file streams.
57 const quill::LogLevel ROVECOMM_DEFAULT_LEVEL = quill::LogLevel::Info; // The default logging level for RoveComm stream.
58
59 // Logging color constants.
60 const std::string szTraceL3Color = "\033[30m"; // Standard Grey
61 const std::string szTraceL2Color = "\033[30m"; // Standard Grey
62 const std::string szTraceL1Color = "\033[30m"; // Standard Grey
63 const std::string szDebugColor = "\033[36m"; // Standard Cyan
64 const std::string szInfoColor = "\033[32m"; // Standard Green
65 const std::string szNoticeColor = "\033[97m\033[1m"; // Bright Bold White
66 const std::string szWarningColor = "\033[93m\033[1m"; // Bright Bold Yellow
67 const std::string szErrorColor = "\033[91m\033[1m"; // Bright Bold Red
68 const std::string szCriticalColor = "\033[95m\033[1m"; // Bright Bold Magenta
69 const std::string szBacktraceColor = "\033[30m"; // Standard Grey
70
71 // RoveComm constants.
72 const int ROVECOMM_OUTGOING_UDP_PORT = MODE_SIM ? 11001 : 11000; // The UDP socket port to use for the main UDP RoveComm instance.
73 const int ROVECOMM_OUTGOING_TCP_PORT = MODE_SIM ? 12001 : 12000; // The UDP socket port to use for the main UDP RoveComm instance.
74 const std::string ROVECOMM_TCP_INTERFACE_IP = ""; // The IP address to bind the socket to. If set to "", the socket will be bound to all available interfaces.
76
80
81 // Power constants.
82 const float DRIVE_MAX_POWER = 1.0;
83 const float DRIVE_MIN_POWER = -1.0;
84 const float DRIVE_MAX_EFFORT = 0.5;
85 const float DRIVE_MIN_EFFORT = -0.5;
86
87 // Control constants.
88 const double DRIVE_PID_PROPORTIONAL = 0.01; // The proportional gain for the controller used to point the rover at a goal heading during navigation.
89 const double DRIVE_PID_INTEGRAL = 0.005; // The integral gain for the controller used to point the rover at a goal heading during navigation.
90 const double DRIVE_PID_DERIVATIVE = 0.02; // The derivative gain for the controller used to point the rover at a goal heading during navigation.
91 const double DRIVE_PID_FEEDFORWARD = 0.0; // The feedforward for the controller used to predict control output.
92 const double DRIVE_PID_MAX_ERROR_PER_ITER = 180; // The max allowable error the controller will see per iteration. This is on degrees from setpoint.
93 const double DRIVE_PID_MAX_INTEGRAL_TERM = 0.15; // The max effort the I term is allowed to contribute.
94 const double DRIVE_PID_MAX_RAMP_RATE = 0.08; // The max ramp rate of the output of the PID controller.
95 const double DRIVE_PID_OUTPUT_FILTER = 0.78; // Larger values will filter out large spikes or oscillations. 0.1 is a good starting point.
96 const double DRIVE_PID_TOLERANCE = 1.0; // The max allowable error from the setpoint for the controller to be considered at the setpoint.
97 const bool DRIVE_PID_OUTPUT_REVERSED = false; // Negates the output of the PID controller.
98 const bool DRIVE_SQUARE_CONTROL_INPUTS = false; // This is used by the DifferentialDrive algorithms. True makes fine inputs smoother, but less responsive.
99 const bool DRIVE_CURVATURE_KINEMATICS_ALLOW_TURN_WHILE_STOPPED = true; // This enabled turning in-place when using curvature drive control.
101
105
106 // Recording adjustments.
107 const int RECORDER_FPS = 15; // The FPS all recordings should run at.
108 // Camera recording toggles.
109 const bool ZED_MAINCAM_ENABLE_RECORDING = true; // Whether or not to record the main ZED camera.
110 const bool ZED_LEFTCAM_ENABLE_RECORDING = true; // Whether or not to record the left ZED camera.
111 const bool ZED_RIGHTCAM_ENABLE_RECORDING = true; // Whether or not to record the right ZED camera.
112 const bool BASICCAM_GROUNDCAM_ENABLE_RECORDING = true; // Whether or not to record the ground USB camera.
113 // TagDetector recording toggles.
114 const bool TAGDETECT_MAINCAM_ENABLE_RECORDING = true; // Whether or not to record the main ZED camera tag detector.
115 const bool TAGDETECT_LEFTCAM_ENABLE_RECORDING = true; // Whether or not to record the left ZED camera tag detector.
116 const bool TAGDETECT_RIGHTCAM_ENABLE_RECORDING = true; // Whether or not to record the right ZED camera tag detector.
117 const bool TAGDETECT_GROUNDCAM_ENABLE_RECORDING = true; // Whether of not to record the ground USB camera tag detector.
119
123
124 // ZedCam Basic Config.
125 const sl::RESOLUTION ZED_BASE_RESOLUTION = sl::RESOLUTION::HD720; // The base resolution to open the all cameras with.
126 const sl::UNIT ZED_MEASURE_UNITS = sl::UNIT::METER; // The base measurement unit to use for depth.
127 const sl::COORDINATE_SYSTEM ZED_COORD_SYSTEM = sl::COORDINATE_SYSTEM::LEFT_HANDED_Y_UP; // Coordinate system to use for measurements.
128 const sl::DEPTH_MODE ZED_DEPTH_MODE = sl::DEPTH_MODE::NEURAL; // The measurement accuracy for depth. NEURAL is by far the best.
129 const sl::VIEW ZED_RETRIEVE_VIEW = sl::VIEW::LEFT; // The eye to retrieve regular and depth images from.
130 const bool ZED_SDK_VERBOSE = false; // Enable verbose output from the internal Camera library in the ZEDSDK.
131 const bool ZED_SENSING_FILL = false; // True provides a depth map with a Z value for every pixel (X, Y) in the left image. Slower and worse.
132 const float ZED_DEFAULT_MINIMUM_DISTANCE = 0.5; // Minimum distance in ZED_MEASURE_UNITS to report from depth measurement.
133 const float ZED_DEFAULT_MAXIMUM_DISTANCE = 40.0; // Maximum distance in ZED_MEASURE_UNITS to report from depth measurement.
134 const float ZED_DEFAULT_FLOOR_PLANE_ERROR = 0.5; // The maximum distance that an estimated floor plane can be from the height of the camera from the ground.
135 const int ZED_DEPTH_STABILIZATION = 1; // This parameter controls a stabilization filter that reduces oscillations in depth map. In the range [0-100]
136 // ZedCam SVO Recording Config.
137 const sl::SVO_COMPRESSION_MODE ZED_SVO_COMPRESSION = sl::SVO_COMPRESSION_MODE::H265; // SVO file compression. H264/H265 minimally affect performance, but need GPU.
138 const int ZED_SVO_BITRATE = 0; // The video bitrate in kbits/s. 0 or [1000-60000]
139 // ZedCam Positional Tracking Config.
140 const sl::POSITIONAL_TRACKING_MODE ZED_POSETRACK_MODE = sl::POSITIONAL_TRACKING_MODE::GEN_1; // Positional tracking accuracy.
141 const bool ZED_POSETRACK_AREA_MEMORY = true; // Enabled camera to remember its surroundings for better positioning. Uses more resources.
142 const bool ZED_POSETRACK_POSE_SMOOTHING = false; // Smooth pose correction for small drift. Decreases overall precision for small movements.
143 const bool ZED_POSETRACK_FLOOR_IS_ORIGIN = true; // Sets the floor plane as origin for tracking. This turns on floor plane detection temporarily.
144 const bool ZED_POSETRACK_ENABLE_IMU_FUSION = true; // Allows ZED to use both optical odometry and IMU data for pose tracking.
145 const float ZED_POSETRACK_USABLE_DEPTH_MIN = 0.75; // Minimum depth used for pose tracking, useful if a static object is partial in view of the camera.
146 const bool ZED_POSETRACK_USE_GRAVITY_ORIGIN = true; // Override 2 of the 3 rotations from initial_world_transform using the IMU.
147 // ZedCam Spatial Mapping Config.
148 const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE ZED_MAPPING_TYPE = sl::SpatialMappingParameters::SPATIAL_MAP_TYPE::MESH; // Mesh or point cloud output.
149 const float ZED_MAPPING_RANGE_METER = 20.0f; // The max range in meters that the ZED cameras should use for mapping. 0 = auto.
150 const float ZED_MAPPING_RESOLUTION_METER = 0.03f; // The approx goal precision for spatial mapping in METERS. Higher = Faster.
151 const int ZED_MAPPING_MAX_MEMORY = 4096; // The max amount of CPU RAM (MB) that can be allocated for spatial mapping.
152 const bool ZED_MAPPING_USE_CHUNK_ONLY = true; // Only update chunks that have probably changed or have new data. Faster, less accurate.
153 const int ZED_MAPPING_STABILITY_COUNTER = 3; // Number of times that a point should be seen before adding to mesh.
154 // ZedCam Object Detection Config.
155 const bool ZED_OBJDETECTION_TRACK_OBJ = true; // Whether or not to enable object tracking in the scene. Attempts to maintain OBJ UUIDs.
156 const bool ZED_OBJDETECTION_SEGMENTATION = false; // Use depth data to compute the segmentation for an object. (exact outline/shape)
157 const sl::OBJECT_FILTERING_MODE ZED_OBJDETECTION_FILTERING = sl::OBJECT_FILTERING_MODE::NMS3D_PER_CLASS; // Custom detection, use PER_CLASS or NONE.
158 const float ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT = 0.5; // 0-1 second. Timeout to keep guessing object position when not in sight.
159 const float ZED_OBJDETECTION_BATCH_RETENTION_TIME = 240; // The time in seconds to search for an object UUID before expiring the object.
160 const float ZED_OBJDETECTION_BATCH_LATENCY = 2; // Short latency will limit the search for previously seen object IDs but will be closer to real time output.
161 // Zed Fusion Config.
162 const sl::UNIT FUSION_MEASUREMENT_UNITS = ZED_MEASURE_UNITS; // The base measurement unit to use for depth and other measurements.
163 const sl::COORDINATE_SYSTEM FUSION_COORD_SYSTEM = ZED_COORD_SYSTEM; // Coordinate system to use for measurements.
164 const bool FUSION_SDK_VERBOSE = false; // Enable verbose output from the internal fusion library in the ZEDSDK.
165 const bool FUSION_ENABLE_GNSS_FUSION = true; // Enable the fusion of camera visual odometry tracking with GNSS data from NavBoard.
166
167 // BasicCam Basic Config.
168 const cv::InterpolationFlags BASICCAM_RESIZE_INTERPOLATION_METHOD = cv::InterpolationFlags::INTER_LINEAR; // The algorithm used to fill in pixels when resizing.
170
174
175 // Main ZED Camera.
176 const int ZED_MAINCAM_RESOLUTIONX = 1280; // The horizontal pixel resolution to resize the maincam images to.
177 const int ZED_MAINCAM_RESOLUTIONY = 720; // The vertical pixel resolution to resize the maincam images to.
178 const int ZED_MAINCAM_FPS = 60; // The FPS to use for the maincam.
179 const int ZED_MAINCAM_HORIZONTAL_FOV = 110; // The horizontal FOV of the camera. Useful for future calculations.
180 const int ZED_MAINCAM_VERTICAL_FOV = 70; // The vertical FOV of the camera. Useful for future calculations.
181 const bool ZED_MAINCAM_USE_GPU_MAT = MODE_SIM ? false : true; // Whether or not to use CPU or GPU memory mats. GPU memory transfer/operations are faster.
182 const bool ZED_MAINCAM_USE_HALF_PRECISION_DEPTH = true; // Whether of not to use float32 or unsigned short (16) for depth measure.
183 const bool ZED_MAINCAM_FUSION_MASTER = false; // Whether or not this camera will host the master instance of the ZEDSDK Fusion capabilities.
184 const int ZED_MAINCAM_FRAME_RETRIEVAL_THREADS = 10; // The number of threads allocated to the threadpool for performing frame copies to other threads.
185 const int ZED_MAINCAM_SERIAL = 15723847; // The serial number of the camera. Set to 0 to open the next available one. 31237348
186
187 // Left ZED Camera.
188 const int ZED_LEFTCAM_RESOLUTIONX = 1280; // The horizontal pixel resolution to resize the leftcam images to.
189 const int ZED_LEFTCAM_RESOLUTIONY = 720; // The vertical pixel resolution to resize the leftcam images to.
190 const int ZED_LEFTCAM_FPS = 60; // The FPS to use for the leftcam.
191 const int ZED_LEFTCAM_HORIZONTAL_FOV = 110; // The horizontal FOV of the camera. Useful for future calculations.
192 const int ZED_LEFTCAM_VERTICAL_FOV = 70; // The vertical FOV of the camera. Useful for future calculations.
193 const bool ZED_LEFTCAM_USE_GPU_MAT = MODE_SIM ? false : true; // Whether or not to use CPU or GPU memory mats. GPU memory transfer/operations are faster.
194 const bool ZED_LEFTCAM_USE_HALF_PRECISION_DEPTH = true; // Whether of not to use float32 or unsigned short (16) for depth measure.
195 const bool ZED_LEFTCAM_FUSION_MASTER = false; // Whether or not this camera will host the master instance of the ZEDSDK Fusion capabilities.
196 const int ZED_LEFTCAM_FRAME_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing frame copies to other threads.
197 const int ZED_LEFTCAM_SERIAL = 0; // The serial number of the camera. Set to 0 to open the next available one. 15723847
198
199 // Right ZED Camera.
200 const int ZED_RIGHTCAM_RESOLUTIONX = 1280; // The horizontal pixel resolution to resize the rightcam images to.
201 const int ZED_RIGHTCAM_RESOLUTIONY = 720; // The vertical pixel resolution to resize the rightcam images to.
202 const int ZED_RIGHTCAM_FPS = 60; // The FPS to use for the rightcam.
203 const int ZED_RIGHTCAM_HORIZONTAL_FOV = 110; // The horizontal FOV of the camera. Useful for future calculations.
204 const int ZED_RIGHTCAM_VERTICAL_FOV = 70; // The vertical FOV of the camera. Useful for future calculations.
205 const bool ZED_RIGHTCAM_USE_GPU_MAT = MODE_SIM ? false : true; // Whether or not to use CPU or GPU memory mats. GPU memory transfer/operations are faster.
206 const bool ZED_RIGHTCAM_USE_HALF_PRECISION_DEPTH = true; // Whether of not to use float32 or unsigned short (16) for depth measure.
207 const bool ZED_RIGHTCAM_FUSION_MASTER = false; // Whether or not this camera will host the master instance of the ZEDSDK Fusion capabilities.
208 const int ZED_RIGHTCAM_FRAME_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing frame copies to other threads.
209 const int ZED_RIGHTCAM_SERIAL = 0; // The serial number of the camera. Set to 0 to open the next available one. 0
210
211 // Ground Basic Cam.
212 const int BASICCAM_GROUNDCAM_RESOLUTIONX = 1280; // The horizontal pixel resolution to resize the basiccam images to.
213 const int BASICCAM_GROUNDCAM_RESOLUTIONY = 720; // The vertical pixel resolution to resize the basiccam images to.
214 const int BASICCAM_GROUNDCAM_FPS = 30; // The FPS to use for the basiccam.
215 const int BASICCAM_GROUNDCAM_HORIZONTAL_FOV = 110; // The horizontal FOV of the camera. Useful for future calculations.
216 const int BASICCAM_GROUNDCAM_VERTICAL_FOV = 70; // The vertical FOV of the camera. Useful for future calculations.
217 const int BASICCAM_GROUNDCAM_FRAME_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing frame copies to other threads.
218 const int BASICCAM_GROUNDCAM_INDEX = 0; // The /dev/video index of the camera.
219 const PIXEL_FORMATS BASICCAM_GROUNDCAM_PIXELTYPE = PIXEL_FORMATS::eBGR; // The pixel layout of the camera.
221
225
226 // OpenCV ArUco detection config.
227 const cv::aruco::PredefinedDictionaryType ARUCO_DICTIONARY = cv::aruco::DICT_4X4_50; // The predefined ArUco dictionary to use for detections.
228 const float ARUCO_TAG_SIDE_LENGTH = 0.015f; // Size of the white borders around the tag in meters.
229 const int ARUCO_VALIDATION_THRESHOLD = 10; // How many times does the tag need to be detected(hit) before being validated as an actual aruco tag.
230 const int ARUCO_UNVALIDATED_TAG_FORGET_THRESHOLD = 5; // How many times can an unvalidated tag be missing from frame before being forgotten.
231 const int ARUCO_VALIDATED_TAG_FORGET_THRESHOLD = 10; // How many times can a validated tag be missing from frame before being forgotten.
232 const double ARUCO_PIXEL_THRESHOLD = 175; // Pixel value threshold for pre-process threshold mask
233 const double ARUCO_PIXEL_THRESHOLD_MAX_VALUE = 255; // Pixel value to set to if pixel is within threshold
234 const cv::Mat ARUCO_SHARPEN_KERNEL_FAST = (cv::Mat_<double>(3, 3) << 0, 0, 0, 0, 3, 0, 0, 0, 0);
235 const cv::Mat ARUCO_SHARPEN_KERNEL_EXTRA = (cv::Mat_<double>(3, 3) << 0, 0, 0, 0, 9, 0, 0, 0, 0);
237
241
242 // Main ZED Camera.
243 const int TAGDETECT_MAINCAM_DATA_RETRIEVAL_THREADS = 2; // The number of threads allocated to the threadpool for performing data copies to other threads.
244 const int TAGDETECT_MAINCAM_CORNER_REFINE_MAX_ITER = 30; // The maximum number of iterations to run corner refinement on the image.
245 const int TAGDETECT_MAINCAM_CORNER_REFINE_METHOD = cv::aruco::CORNER_REFINE_NONE; // Algorithm used to refine tag corner pixels.
246 const bool TAGDETECT_MAINCAM_DETECT_INVERTED_MARKER = false; // Whether or not to detector upside-down tags.
247 const int TAGDETECT_MAINCAM_MARKER_BORDER_BITS = 1; // This number of bits on the border. A bit is one unit square of the tag.
248 const bool TAGDETECT_MAINCAM_USE_ARUCO3_DETECTION = true; // Whether or not to use the newer and faster Aruco detection strategy.
249 const int TAGDETECT_MAINCAM_MAX_FPS = 30; // The max iterations per second of the tag detector.
250 const bool TAGDETECT_MAINCAM_ENABLE_DNN = false; // Whether or not to use DNN detection on top of ArUco.
251 const std::string TAGDETECT_MAINCAM_MODEL_PATH = "../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite"; // The model path to use for detection.
252 const float TAGDETECT_MAINCAM_DNN_CONFIDENCE = 0.4f; // The minimum confidence to consider a viable AR tag detection.
253 const float TAGDETECT_MAINCAM_DNN_NMS_THRESH = 0.4f; // The threshold for non-max suppression filtering.
254
255 // Left ZED Camera.
256 const int TAGDETECT_LEFTCAM_DATA_RETRIEVAL_THREADS = 2; // The number of threads allocated to the threadpool for performing data copies to other threads.
257 const int TAGDETECT_LEFTCAM_CORNER_REFINE_MAX_ITER = 30; // The maximum number of iterations to run corner refinement on the image.
258 const int TAGDETECT_LEFTCAM_CORNER_REFINE_METHOD = cv::aruco::CORNER_REFINE_NONE; // Algorithm used to refine tag corner pixels.
259 const bool TAGDETECT_LEFTCAM_DETECT_INVERTED_MARKER = false; // Whether or not to detector upside-down tags.
260 const int TAGDETECT_LEFTCAM_MARKER_BORDER_BITS = 1; // This number of bits on the border. A bit is one unit square of the tag.
261 const bool TAGDETECT_LEFTCAM_USE_ARUCO3_DETECTION = true; // Whether or not to use the newer and faster Aruco detection strategy.
262 const int TAGDETECT_LEFTCAM_MAX_FPS = 30; // The max iterations per second of the tag detector.
263 const bool TAGDETECT_LEFTCAM_ENABLE_DNN = false; // Whether or not to use DNN detection on top of ArUco.
264 const std::string TAGDETECT_LEFTCAM_MODEL_PATH = "../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite"; // The model path to use for detection.
265 const float TAGDETECT_LEFTCAM_DNN_CONFIDENCE = 0.4f; // The minimum confidence to consider a viable AR tag detection.
266 const float TAGDETECT_LEFTCAM_DNN_NMS_THRESH = 0.4f; // The threshold for non-max suppression filtering.
267
268 // Right ZED Camera.
269 const int TAGDETECT_RIGHTCAM_DATA_RETRIEVAL_THREADS = 2; // The number of threads allocated to the threadpool for performing data copies to other threads.
270 const int TAGDETECT_RIGHTCAM_CORNER_REFINE_MAX_ITER = 30; // The maximum number of iterations to run corner refinement on the image.
271 const int TAGDETECT_RIGHTCAM_CORNER_REFINE_METHOD = cv::aruco::CORNER_REFINE_NONE; // Algorithm used to refine tag corner pixels.
272 const bool TAGDETECT_RIGHTCAM_DETECT_INVERTED_MARKER = false; // Whether or not to detector upside-down tags.
273 const int TAGDETECT_RIGHTCAM_MARKER_BORDER_BITS = 1; // This number of bits on the border. A bit is one unit square of the tag.
274 const bool TAGDETECT_RIGHTCAM_USE_ARUCO3_DETECTION = true; // Whether or not to use the newer and faster Aruco detection strategy.
275 const int TAGDETECT_RIGHTCAM_MAX_FPS = 30; // The max iterations per second of the tag detector.
276 const bool TAGDETECT_RIGHTCAM_ENABLE_DNN = false; // Whether or not to use DNN detection on top of ArUco.
277 const std::string TAGDETECT_RIGHTCAM_MODEL_PATH = "../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite"; // The model path to use for detection.
278 const float TAGDETECT_RIGHTCAM_DNN_CONFIDENCE = 0.4f; // The minimum confidence to consider a viable AR tag detection.
279 const float TAGDETECT_RIGHTCAM_DNN_NMS_THRESH = 0.4f; // The threshold for non-max suppression filtering.
280
284
285 // Main ZED Camera.
286 const int OBJECTDETECT_MAINCAM_DATA_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing data copies to other threads.
287
288 // Left Side Cam.
289 const int OBJECTDETECT_LEFTCAM_DATA_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing data copies to other threads.
290
291 // Right Side Cam.
292 const int OBJECTDETECT_RIGHTCAM_DATA_RETRIEVAL_THREADS = 5; // The number of threads allocated to the threadpool for performing data copies to other threads.
294
298
299 // Approaching Marker State
300 const int APPROACH_MARKER_DETECT_ATTEMPTS_LIMIT = 5; // How many consecutive failed attempts at detecting a tag before giving up on marker.
301 const double APPROACH_MARKER_MOTOR_POWER = 0.3; // The amount of power the motors use when approaching the marker.
302 const double APPROACH_MARKER_PROXIMITY_THRESHOLD = 2.0; // How close in meters the rover must be to the target marker before completing its approach.
303 const double APPROACH_MARKER_TF_CONFIDENCE_THRESHOLD = 0.5; // What is the minimal confidence necessary to consider a tensorflow tag as a target.
304
305 // Stuck State
306 const double STUCK_CHECK_INTERVAL = 2.0; // Period in seconds between consecutive checks of if the rover's rotating.
307 const unsigned int STUCK_CHECK_ATTEMPTS = 3; // Max number of failed checks of the rover's rotation before next attempt.
308 const double STUCK_CHECK_ROT_THRESH = 10.0; // Minimum angular velocity required to consider the rover as actively rotating.
309 const double STUCK_CHECK_VEL_THRESH = 0.5; // Minimum velocity required to consider the rover as actively moving.
310 const double STUCK_SAME_POINT_PROXIMITY = 1.0; // Points within this proximity of another point are considered the same.
311 const double STUCK_HEADING_ALIGN_TIMEOUT = 5.0; // The timeout in seconds before the rover gives up aligning to a certain heading.
312 const double STUCK_ALIGN_DEGREES = 65.0; // The amount to rotate/realign for rover after a failed attempt.
313 const double STUCK_ALIGN_TOLERANCE = 5.0; // Degree tolerance before realignment is considered complete.
314
315 // Reverse State.
316 const double REVERSE_MOTOR_POWER = DRIVE_MAX_POWER; // The speed to drive backwards at.
317 const double REVERSE_DISTANCE = 3.0; // The distance to reverse in meters.
318 const double REVERSE_TIMEOUT_PER_METER = 5.0; // Reverse state timeout in seconds for each meter reversed.
319 const bool REVERSE_MAINTAIN_HEADING = true; // Whether or not the rover should maintain heading while reversing.
320
321 // Search Pattern State
322 const double SEARCH_ANGULAR_STEP_DEGREES = 57.0; // The amount the angle is incremented in each iteration of the loop (degrees).
323 const double SEARCH_SPIRAL_SPACING = 1.0; // The spacing between successive points in the spiral (meters).
324 const double SEARCH_ZIGZAG_SPACING = 1.0; // The spacing between successive points in the zigzag (meters).
325 const double SEARCH_WAYPOINT_PROXIMITY = 2.0; // How close a rover must be to a point to have it count as visited.
326 const double SEARCH_MOTOR_POWER = 0.5; // The amount of power the motors use when approaching the marker.
327
328 // Handler.
329 const int STATEMACHINE_MAX_IPS = 60; // The maximum number of iteration per second of the state machines main thread.
330 const double STATEMACHINE_ZED_REALIGN_THRESHOLD = 0.5; // The threshold in meters that the error between GPS and ZED must be before realigning the ZED cameras.
331
332 // Navigating State.
333 const double NAVIGATING_REACHED_GOAL_RADIUS = 2.0; // The radius in meters that the rover should get to the goal waypoint.
334
335 // Avoidance State.
336 const double AVOIDANCE_STATE_MOTOR_POWER = DRIVE_MAX_POWER; // Drive speed of avoidance state
337
339
343
344 // High Level Functionality Adjustments.
345
347
351
352 // Stanley Controller config.
353 const double STANLEY_STEER_CONTROL_GAIN = 0.5; // Determines how reactive the rover is to yaw adjustments.
354 const double STANLEY_DIST_TO_FRONT_AXLE = 2.9; // Distance from position sensor to the center of the front axle.
355 const double STANLEY_YAW_TOLERANCE = 1.0; // Threshold for limiting unnecessary small movements.
356
357 // ASTAR config.
358 const double ASTAR_AVOIDANCE_MULTIPLIER = 1.2; // Multiplier for marking extra nodes around objects as obstacles
359 const double ASTAR_MAXIMUM_SEARCH_GRID = 10.0; // Maximum search grid size (UTM)
360 const double ASTAR_NODE_SIZE = 0.5; // Represents the node size / accuracy in meters
361 const double ASTAR_SQRT_NODE_SIZE = M_SQRT1_2; // Square root of m_dNodeSize
362
364
368
369 // NavBoard.
370 const double NAVBOARD_MAX_GPS_DATA_AGE = 3.0; // The maximum age of the current GPS data before printing warnings.
371 const double NAVBOARD_MAX_COMPASS_DATA_AGE = 3.0; // The maximum age of the current Compass data before printing warnings.
372
374
375} // namespace constants
376
377#endif // CONSTS_H
Defines the Camera base interface class.
uint32_t uint
InterpolationFlags
PredefinedDictionaryType
Namespace containing all constants for autonomy software. Including AutonomyGlobals....
Definition AutonomyConstants.h:32