Skip to content

Commit e960ccb

Browse files
Merge pull request autowarefoundation#221 from pranavreddy23/clean_logs
Clean Rerun logs
2 parents adc133e + 8ad75e6 commit e960ccb

File tree

3 files changed

+30
-20
lines changed

3 files changed

+30
-20
lines changed

VisionPilot/Production_Releases/0.5/include/rerun/rerun_logger.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -51,7 +51,8 @@ class RerunLogger {
5151
* @param lanes Lane segmentation masks
5252
* @param stacked_view Final visualization (BGR)
5353
* @param vehicle_state CAN bus data (steering, speed)
54-
* @param steering_angle PID steering angle (radians)
54+
* @param steering_angle_raw Raw PID output before filtering (degrees)
55+
* @param steering_angle Filtered PID output (final steering, degrees)
5556
* @param autosteer_angle AutoSteer steering angle (degrees)
5657
* @param path_output PathFinder output (CTE, yaw, curvature)
5758
* @param inference_time_us Inference time in microseconds
@@ -62,6 +63,7 @@ class RerunLogger {
6263
const autoware_pov::vision::egolanes::LaneSegmentation& lanes,
6364
const cv::Mat& stacked_view,
6465
const autoware_pov::drivers::CanVehicleState& vehicle_state,
66+
double steering_angle_raw,
6567
double steering_angle,
6668
float autosteer_angle,
6769
const autoware_pov::vision::path_planning::PathFinderOutput& path_output,

VisionPilot/Production_Releases/0.5/main.cpp

Lines changed: 21 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -138,7 +138,8 @@ struct InferenceResult {
138138
int frame_number;
139139
steady_clock::time_point capture_time;
140140
steady_clock::time_point inference_time;
141-
double steering_angle = 0.0; // Steering angle from PID controller (radians)
141+
double steering_angle_raw = 0.0; // Raw PID output before filtering (degrees)
142+
double steering_angle = 0.0; // Filtered PID output (final steering, degrees)
142143
PathFinderOutput path_output; // Added for metric debug
143144
float autosteer_angle = 0.0f; // Steering angle from AutoSteer (degrees)
144145
bool autosteer_valid = false; // Whether AutoSteer ran (skips first frame)
@@ -349,6 +350,8 @@ void inferenceThread(
349350
// AUTOSTEER INTEGRATION
350351
// ========================================
351352
float autosteer_steering = 0.0f;
353+
double steering_angle_raw = 0.0;
354+
double steering_angle = 0.0;
352355

353356
if (autosteer_engine != nullptr) {
354357
// 1. Copy raw EgoLanes tensor [1, 3, 80, 160] for temporal buffer
@@ -398,8 +401,7 @@ void inferenceThread(
398401
// ========================================
399402
// PATHFINDER (Polynomial Fitting + Bayes Filter) + STEERING CONTROL
400403
// ========================================
401-
double steering_angle = 0.0; // Initialize steering angle (PID controller output)
402-
PathFinderOutput path_output; // Declare at higher scope for result storage
404+
PathFinderOutput path_output; // Declaring at higher scope for result storage
403405
path_output.fused_valid = false; // Initialize as invalid
404406

405407
if (path_finder != nullptr && final_metrics.bev_visuals.valid) {
@@ -423,15 +425,17 @@ void inferenceThread(
423425
path_output = path_finder->update(left_bev_meters, right_bev_meters, autosteer_steering);
424426

425427
// 4. Compute steering angle (if controller available)
428+
// double steering_angle_raw = 0.0; // Raw PID output before filtering
426429
if (steering_controller != nullptr && path_output.fused_valid) {
427-
steering_angle = steering_controller->computeSteering(
430+
steering_angle_raw = steering_controller->computeSteering(
428431
path_output.cte,
429432
path_output.yaw_error * 180 / M_PI,
430433
path_output.curvature
431434
);
432435
}
433436

434-
steering_angle = steering_filter.filter(steering_angle, 0.1);
437+
// Filter the raw PID output
438+
steering_angle = steering_filter.filter(steering_angle_raw, 0.1);
435439

436440
// 5. Print output (cross-track error, yaw error, curvature, lane width + variances + steering)
437441
if (path_output.fused_valid) {
@@ -485,7 +489,8 @@ void inferenceThread(
485489
result.frame_number = tf.frame_number;
486490
result.capture_time = tf.timestamp;
487491
result.inference_time = t_inference_end;
488-
result.steering_angle = steering_angle; // Store PID steering angle
492+
result.steering_angle_raw = steering_angle_raw; // Store raw PID output (before filtering)
493+
result.steering_angle = steering_angle; // Store filtered PID output (final steering)
489494
result.path_output = path_output; // Store for viz
490495
result.autosteer_angle = autosteer_steering; // Store AutoSteer angle
491496
result.autosteer_valid = (autosteer_engine != nullptr && egolanes_tensor_buffer.full());
@@ -539,12 +544,12 @@ void displayThread(
539544
std::ofstream csv_file;
540545
csv_file.open(csv_log_path);
541546
if (csv_file.is_open()) {
542-
// Write header
543-
csv_file << "frame_id,timestamp_ms,"
544-
<< "orig_lane_offset,orig_yaw_offset,orig_curvature,"
545-
<< "pathfinder_cte,pathfinder_yaw_error,pathfinder_curvature,"
546-
<< "pid_steering_rad,pid_steering_deg,"
547-
<< "autosteer_angle_deg,autosteer_valid\n";
547+
// Write header
548+
csv_file << "frame_id,timestamp_ms,"
549+
<< "orig_lane_offset,orig_yaw_offset,orig_curvature,"
550+
<< "pathfinder_cte,pathfinder_yaw_error,pathfinder_curvature,"
551+
<< "pid_steering_raw_deg,pid_steering_filtered_deg,"
552+
<< "autosteer_angle_deg,autosteer_valid\n";
548553

549554
std::cout << "CSV logging enabled: " << csv_log_path << std::endl;
550555
} else {
@@ -611,7 +616,8 @@ void displayThread(
611616
result.lanes, // Lane masks
612617
view_debug, // Final visualization (with steering wheel + lane masks)
613618
result.vehicle_state, // CAN bus data
614-
result.steering_angle, // PID steering (radians)
619+
result.steering_angle_raw, // Raw PID output (degrees, before filtering)
620+
result.steering_angle, // Filtered PID output (degrees, final steering)
615621
result.autosteer_angle, // AutoSteer steering (degrees)
616622
result.path_output, // PathFinder outputs
617623
inference_time_us // Inference time
@@ -737,8 +743,8 @@ void displayThread(
737743
<< (result.path_output.fused_valid ? result.path_output.cte : 0.0) << ","
738744
<< (result.path_output.fused_valid ? result.path_output.yaw_error : 0.0) << ","
739745
<< (result.path_output.fused_valid ? result.path_output.curvature : 0.0) << ","
740-
// PID Controller steering angle (always log if controller exists)
741-
<< std::fixed << std::setprecision(6) << result.steering_angle * M_PI / 180.0 << ","
746+
// PID Controller steering angles (all in degrees)
747+
<< std::fixed << std::setprecision(6) << result.steering_angle_raw << ","
742748
<< result.steering_angle << ","
743749
// AutoSteer steering angle (degrees) and validity
744750
<< result.autosteer_angle << ","

VisionPilot/Production_Releases/0.5/src/rerun/rerun_logger.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -89,6 +89,7 @@ void RerunLogger::logData(
8989
const autoware_pov::vision::egolanes::LaneSegmentation& lanes,
9090
const cv::Mat& stacked_view,
9191
const autoware_pov::drivers::CanVehicleState& vehicle_state,
92+
double steering_angle_raw,
9293
double steering_angle,
9394
float autosteer_angle,
9495
const autoware_pov::vision::path_planning::PathFinderOutput& path_output,
@@ -127,11 +128,11 @@ void RerunLogger::logData(
127128
rec_->log("can/speed_kmph",
128129
rerun::archetypes::Scalars(rerun::Collection<rerun::components::Scalar>({can_scalars[1]})));
129130

130-
// Log control outputs (scalars)
131-
rec_->log("control/pid_steering_rad",
131+
// Log control outputs (all in degrees)
132+
rec_->log("control/pid_steering_raw_deg",
133+
rerun::archetypes::Scalars(rerun::Collection<rerun::components::Scalar>({rerun::components::Scalar(steering_angle_raw)})));
134+
rec_->log("control/pid_steering_filtered_deg",
132135
rerun::archetypes::Scalars(rerun::Collection<rerun::components::Scalar>({rerun::components::Scalar(steering_angle)})));
133-
rec_->log("control/pid_steering_deg",
134-
rerun::archetypes::Scalars(rerun::Collection<rerun::components::Scalar>({rerun::components::Scalar(steering_angle * 180.0 / M_PI)})));
135136
rec_->log("control/autosteer_angle_deg",
136137
rerun::archetypes::Scalars(rerun::Collection<rerun::components::Scalar>({rerun::components::Scalar(autosteer_angle)})));
137138

@@ -155,6 +156,7 @@ void RerunLogger::logData(
155156
(void)lanes;
156157
(void)stacked_view;
157158
(void)vehicle_state;
159+
(void)steering_angle_raw;
158160
(void)steering_angle;
159161
(void)autosteer_angle;
160162
(void)path_output;

0 commit comments

Comments
 (0)