38#if defined(__AUTONOMY_SIM_MODE__) && __AUTONOMY_SIM_MODE__ == 1
39 const bool MODE_SIM =
true;
41 const bool MODE_SIM =
false;
43 const std::string SIM_IP_ADDRESS =
"192.168.69.29";
44 const uint SIM_WEBRTC_QP = 25;
47 const double BATTERY_MINIMUM_CELL_VOLTAGE = 3.2;
48 const bool BATTERY_CHECKS_ENABLED =
false;
51 const std::string LOGGING_OUTPUT_PATH_ABSOLUTE =
"../logs/";
52 const quill::LogLevel CONSOLE_MIN_LEVEL = quill::LogLevel::TraceL3;
53 const quill::LogLevel FILE_MIN_LEVEL = quill::LogLevel::TraceL3;
54 const quill::LogLevel ROVECOMM_MIN_LEVEL = quill::LogLevel::Info;
55 const quill::LogLevel CONSOLE_DEFAULT_LEVEL = quill::LogLevel::Info;
56 const quill::LogLevel FILE_DEFAULT_LEVEL = quill::LogLevel::TraceL3;
57 const quill::LogLevel ROVECOMM_DEFAULT_LEVEL = quill::LogLevel::Info;
60 const std::string szTraceL3Color =
"\033[30m";
61 const std::string szTraceL2Color =
"\033[30m";
62 const std::string szTraceL1Color =
"\033[30m";
63 const std::string szDebugColor =
"\033[36m";
64 const std::string szInfoColor =
"\033[32m";
65 const std::string szNoticeColor =
"\033[97m\033[1m";
66 const std::string szWarningColor =
"\033[93m\033[1m";
67 const std::string szErrorColor =
"\033[91m\033[1m";
68 const std::string szCriticalColor =
"\033[95m\033[1m";
69 const std::string szBacktraceColor =
"\033[30m";
72 const int ROVECOMM_OUTGOING_UDP_PORT = MODE_SIM ? 11001 : 11000;
73 const int ROVECOMM_OUTGOING_TCP_PORT = MODE_SIM ? 12001 : 12000;
74 const std::string ROVECOMM_TCP_INTERFACE_IP =
"";
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;
88 const double DRIVE_PID_PROPORTIONAL = 0.01;
89 const double DRIVE_PID_INTEGRAL = 0.005;
90 const double DRIVE_PID_DERIVATIVE = 0.02;
91 const double DRIVE_PID_FEEDFORWARD = 0.0;
92 const double DRIVE_PID_MAX_ERROR_PER_ITER = 180;
93 const double DRIVE_PID_MAX_INTEGRAL_TERM = 0.15;
94 const double DRIVE_PID_MAX_RAMP_RATE = 0.08;
95 const double DRIVE_PID_OUTPUT_FILTER = 0.78;
96 const double DRIVE_PID_TOLERANCE = 1.0;
97 const bool DRIVE_PID_OUTPUT_REVERSED =
false;
98 const bool DRIVE_SQUARE_CONTROL_INPUTS =
false;
99 const bool DRIVE_CURVATURE_KINEMATICS_ALLOW_TURN_WHILE_STOPPED =
true;
107 const int RECORDER_FPS = 15;
109 const bool ZED_MAINCAM_ENABLE_RECORDING =
true;
110 const bool ZED_LEFTCAM_ENABLE_RECORDING =
true;
111 const bool ZED_RIGHTCAM_ENABLE_RECORDING =
true;
112 const bool BASICCAM_GROUNDCAM_ENABLE_RECORDING =
true;
114 const bool TAGDETECT_MAINCAM_ENABLE_RECORDING =
true;
115 const bool TAGDETECT_LEFTCAM_ENABLE_RECORDING =
true;
116 const bool TAGDETECT_RIGHTCAM_ENABLE_RECORDING =
true;
117 const bool TAGDETECT_GROUNDCAM_ENABLE_RECORDING =
true;
125 const sl::RESOLUTION ZED_BASE_RESOLUTION = sl::RESOLUTION::HD720;
126 const sl::UNIT ZED_MEASURE_UNITS = sl::UNIT::METER;
127 const sl::COORDINATE_SYSTEM ZED_COORD_SYSTEM = sl::COORDINATE_SYSTEM::LEFT_HANDED_Y_UP;
128 const sl::DEPTH_MODE ZED_DEPTH_MODE = sl::DEPTH_MODE::NEURAL;
129 const sl::VIEW ZED_RETRIEVE_VIEW = sl::VIEW::LEFT;
130 const bool ZED_SDK_VERBOSE =
false;
131 const bool ZED_SENSING_FILL =
false;
132 const float ZED_DEFAULT_MINIMUM_DISTANCE = 0.5;
133 const float ZED_DEFAULT_MAXIMUM_DISTANCE = 40.0;
134 const float ZED_DEFAULT_FLOOR_PLANE_ERROR = 0.5;
135 const int ZED_DEPTH_STABILIZATION = 1;
137 const sl::SVO_COMPRESSION_MODE ZED_SVO_COMPRESSION = sl::SVO_COMPRESSION_MODE::H265;
138 const int ZED_SVO_BITRATE = 0;
140 const sl::POSITIONAL_TRACKING_MODE ZED_POSETRACK_MODE = sl::POSITIONAL_TRACKING_MODE::GEN_1;
141 const bool ZED_POSETRACK_AREA_MEMORY =
true;
142 const bool ZED_POSETRACK_POSE_SMOOTHING =
false;
143 const bool ZED_POSETRACK_FLOOR_IS_ORIGIN =
true;
144 const bool ZED_POSETRACK_ENABLE_IMU_FUSION =
true;
145 const float ZED_POSETRACK_USABLE_DEPTH_MIN = 0.75;
146 const bool ZED_POSETRACK_USE_GRAVITY_ORIGIN =
true;
148 const sl::SpatialMappingParameters::SPATIAL_MAP_TYPE ZED_MAPPING_TYPE = sl::SpatialMappingParameters::SPATIAL_MAP_TYPE::MESH;
149 const float ZED_MAPPING_RANGE_METER = 20.0f;
150 const float ZED_MAPPING_RESOLUTION_METER = 0.03f;
151 const int ZED_MAPPING_MAX_MEMORY = 4096;
152 const bool ZED_MAPPING_USE_CHUNK_ONLY =
true;
153 const int ZED_MAPPING_STABILITY_COUNTER = 3;
155 const bool ZED_OBJDETECTION_TRACK_OBJ =
true;
156 const bool ZED_OBJDETECTION_SEGMENTATION =
false;
157 const sl::OBJECT_FILTERING_MODE ZED_OBJDETECTION_FILTERING = sl::OBJECT_FILTERING_MODE::NMS3D_PER_CLASS;
158 const float ZED_OBJDETECTION_TRACKING_PREDICTION_TIMEOUT = 0.5;
159 const float ZED_OBJDETECTION_BATCH_RETENTION_TIME = 240;
160 const float ZED_OBJDETECTION_BATCH_LATENCY = 2;
162 const sl::UNIT FUSION_MEASUREMENT_UNITS = ZED_MEASURE_UNITS;
163 const sl::COORDINATE_SYSTEM FUSION_COORD_SYSTEM = ZED_COORD_SYSTEM;
164 const bool FUSION_SDK_VERBOSE =
false;
165 const bool FUSION_ENABLE_GNSS_FUSION =
true;
176 const int ZED_MAINCAM_RESOLUTIONX = 1280;
177 const int ZED_MAINCAM_RESOLUTIONY = 720;
178 const int ZED_MAINCAM_FPS = 60;
179 const int ZED_MAINCAM_HORIZONTAL_FOV = 110;
180 const int ZED_MAINCAM_VERTICAL_FOV = 70;
181 const bool ZED_MAINCAM_USE_GPU_MAT = MODE_SIM ? false :
true;
182 const bool ZED_MAINCAM_USE_HALF_PRECISION_DEPTH =
true;
183 const bool ZED_MAINCAM_FUSION_MASTER =
false;
184 const int ZED_MAINCAM_FRAME_RETRIEVAL_THREADS = 10;
185 const int ZED_MAINCAM_SERIAL = 15723847;
188 const int ZED_LEFTCAM_RESOLUTIONX = 1280;
189 const int ZED_LEFTCAM_RESOLUTIONY = 720;
190 const int ZED_LEFTCAM_FPS = 60;
191 const int ZED_LEFTCAM_HORIZONTAL_FOV = 110;
192 const int ZED_LEFTCAM_VERTICAL_FOV = 70;
193 const bool ZED_LEFTCAM_USE_GPU_MAT = MODE_SIM ? false :
true;
194 const bool ZED_LEFTCAM_USE_HALF_PRECISION_DEPTH =
true;
195 const bool ZED_LEFTCAM_FUSION_MASTER =
false;
196 const int ZED_LEFTCAM_FRAME_RETRIEVAL_THREADS = 5;
197 const int ZED_LEFTCAM_SERIAL = 0;
200 const int ZED_RIGHTCAM_RESOLUTIONX = 1280;
201 const int ZED_RIGHTCAM_RESOLUTIONY = 720;
202 const int ZED_RIGHTCAM_FPS = 60;
203 const int ZED_RIGHTCAM_HORIZONTAL_FOV = 110;
204 const int ZED_RIGHTCAM_VERTICAL_FOV = 70;
205 const bool ZED_RIGHTCAM_USE_GPU_MAT = MODE_SIM ? false :
true;
206 const bool ZED_RIGHTCAM_USE_HALF_PRECISION_DEPTH =
true;
207 const bool ZED_RIGHTCAM_FUSION_MASTER =
false;
208 const int ZED_RIGHTCAM_FRAME_RETRIEVAL_THREADS = 5;
209 const int ZED_RIGHTCAM_SERIAL = 0;
212 const int BASICCAM_GROUNDCAM_RESOLUTIONX = 1280;
213 const int BASICCAM_GROUNDCAM_RESOLUTIONY = 720;
214 const int BASICCAM_GROUNDCAM_FPS = 30;
215 const int BASICCAM_GROUNDCAM_HORIZONTAL_FOV = 110;
216 const int BASICCAM_GROUNDCAM_VERTICAL_FOV = 70;
217 const int BASICCAM_GROUNDCAM_FRAME_RETRIEVAL_THREADS = 5;
218 const int BASICCAM_GROUNDCAM_INDEX = 0;
219 const PIXEL_FORMATS BASICCAM_GROUNDCAM_PIXELTYPE = PIXEL_FORMATS::eBGR;
228 const float ARUCO_TAG_SIDE_LENGTH = 0.015f;
229 const int ARUCO_VALIDATION_THRESHOLD = 10;
230 const int ARUCO_UNVALIDATED_TAG_FORGET_THRESHOLD = 5;
231 const int ARUCO_VALIDATED_TAG_FORGET_THRESHOLD = 10;
232 const double ARUCO_PIXEL_THRESHOLD = 175;
233 const double ARUCO_PIXEL_THRESHOLD_MAX_VALUE = 255;
243 const int TAGDETECT_MAINCAM_DATA_RETRIEVAL_THREADS = 2;
244 const int TAGDETECT_MAINCAM_CORNER_REFINE_MAX_ITER = 30;
246 const bool TAGDETECT_MAINCAM_DETECT_INVERTED_MARKER =
false;
247 const int TAGDETECT_MAINCAM_MARKER_BORDER_BITS = 1;
248 const bool TAGDETECT_MAINCAM_USE_ARUCO3_DETECTION =
true;
249 const int TAGDETECT_MAINCAM_MAX_FPS = 30;
250 const bool TAGDETECT_MAINCAM_ENABLE_DNN =
false;
251 const std::string TAGDETECT_MAINCAM_MODEL_PATH =
"../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite";
252 const float TAGDETECT_MAINCAM_DNN_CONFIDENCE = 0.4f;
253 const float TAGDETECT_MAINCAM_DNN_NMS_THRESH = 0.4f;
256 const int TAGDETECT_LEFTCAM_DATA_RETRIEVAL_THREADS = 2;
257 const int TAGDETECT_LEFTCAM_CORNER_REFINE_MAX_ITER = 30;
259 const bool TAGDETECT_LEFTCAM_DETECT_INVERTED_MARKER =
false;
260 const int TAGDETECT_LEFTCAM_MARKER_BORDER_BITS = 1;
261 const bool TAGDETECT_LEFTCAM_USE_ARUCO3_DETECTION =
true;
262 const int TAGDETECT_LEFTCAM_MAX_FPS = 30;
263 const bool TAGDETECT_LEFTCAM_ENABLE_DNN =
false;
264 const std::string TAGDETECT_LEFTCAM_MODEL_PATH =
"../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite";
265 const float TAGDETECT_LEFTCAM_DNN_CONFIDENCE = 0.4f;
266 const float TAGDETECT_LEFTCAM_DNN_NMS_THRESH = 0.4f;
269 const int TAGDETECT_RIGHTCAM_DATA_RETRIEVAL_THREADS = 2;
270 const int TAGDETECT_RIGHTCAM_CORNER_REFINE_MAX_ITER = 30;
272 const bool TAGDETECT_RIGHTCAM_DETECT_INVERTED_MARKER =
false;
273 const int TAGDETECT_RIGHTCAM_MARKER_BORDER_BITS = 1;
274 const bool TAGDETECT_RIGHTCAM_USE_ARUCO3_DETECTION =
true;
275 const int TAGDETECT_RIGHTCAM_MAX_FPS = 30;
276 const bool TAGDETECT_RIGHTCAM_ENABLE_DNN =
false;
277 const std::string TAGDETECT_RIGHTCAM_MODEL_PATH =
"../data/models/yolo_models/tag/v5n_x320_200epochs/best_edgetpu.tflite";
278 const float TAGDETECT_RIGHTCAM_DNN_CONFIDENCE = 0.4f;
279 const float TAGDETECT_RIGHTCAM_DNN_NMS_THRESH = 0.4f;
286 const int OBJECTDETECT_MAINCAM_DATA_RETRIEVAL_THREADS = 5;
289 const int OBJECTDETECT_LEFTCAM_DATA_RETRIEVAL_THREADS = 5;
292 const int OBJECTDETECT_RIGHTCAM_DATA_RETRIEVAL_THREADS = 5;
300 const int APPROACH_MARKER_DETECT_ATTEMPTS_LIMIT = 5;
301 const double APPROACH_MARKER_MOTOR_POWER = 0.3;
302 const double APPROACH_MARKER_PROXIMITY_THRESHOLD = 2.0;
303 const double APPROACH_MARKER_TF_CONFIDENCE_THRESHOLD = 0.5;
306 const double STUCK_CHECK_INTERVAL = 2.0;
307 const unsigned int STUCK_CHECK_ATTEMPTS = 3;
308 const double STUCK_CHECK_ROT_THRESH = 10.0;
309 const double STUCK_CHECK_VEL_THRESH = 0.5;
310 const double STUCK_SAME_POINT_PROXIMITY = 1.0;
311 const double STUCK_HEADING_ALIGN_TIMEOUT = 5.0;
312 const double STUCK_ALIGN_DEGREES = 65.0;
313 const double STUCK_ALIGN_TOLERANCE = 5.0;
316 const double REVERSE_MOTOR_POWER = DRIVE_MAX_POWER;
317 const double REVERSE_DISTANCE = 3.0;
318 const double REVERSE_TIMEOUT_PER_METER = 5.0;
319 const bool REVERSE_MAINTAIN_HEADING =
true;
322 const double SEARCH_ANGULAR_STEP_DEGREES = 57.0;
323 const double SEARCH_SPIRAL_SPACING = 1.0;
324 const double SEARCH_ZIGZAG_SPACING = 1.0;
325 const double SEARCH_WAYPOINT_PROXIMITY = 2.0;
326 const double SEARCH_MOTOR_POWER = 0.5;
329 const int STATEMACHINE_MAX_IPS = 60;
330 const double STATEMACHINE_ZED_REALIGN_THRESHOLD = 0.5;
333 const double NAVIGATING_REACHED_GOAL_RADIUS = 2.0;
336 const double AVOIDANCE_STATE_MOTOR_POWER = DRIVE_MAX_POWER;
353 const double STANLEY_STEER_CONTROL_GAIN = 0.5;
354 const double STANLEY_DIST_TO_FRONT_AXLE = 2.9;
355 const double STANLEY_YAW_TOLERANCE = 1.0;
358 const double ASTAR_AVOIDANCE_MULTIPLIER = 1.2;
359 const double ASTAR_MAXIMUM_SEARCH_GRID = 10.0;
360 const double ASTAR_NODE_SIZE = 0.5;
361 const double ASTAR_SQRT_NODE_SIZE = M_SQRT1_2;
370 const double NAVBOARD_MAX_GPS_DATA_AGE = 3.0;
371 const double NAVBOARD_MAX_COMPASS_DATA_AGE = 3.0;