@@ -660,7 +660,7 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m)
660
660
}
661
661
}
662
662
663
- _scale_dist (*distance_m, scaled_yaw, _vehicle_attitude);
663
+ _project_distance_on_horizontal_plane (*distance_m, scaled_yaw, _vehicle_attitude);
664
664
665
665
if (_current_bin_dist > _obstacle_distance.max_distance ) {
666
666
_current_bin_dist = _obstacle_distance.max_distance + 1 ; // As per ObstacleDistance.msg definition
@@ -741,18 +741,17 @@ void SF45LaserSerial::_handle_missed_bins(uint8_t current_bin, uint8_t previous_
741
741
}
742
742
}
743
743
}
744
- void SF45LaserSerial::_scale_dist (float &distance, const int16_t &yaw, const matrix::Quatf &attitude)
744
+ void SF45LaserSerial::_project_distance_on_horizontal_plane (float &distance, const int16_t &yaw,
745
+ const matrix::Quatf &q_world_vehicle)
745
746
{
746
- const Quatf q_sensor (Quatf (cosf (yaw / 2 .f ), 0 .f , 0 .f , sinf (yaw / 2 .f )));
747
- const Vector3f forward_vector (1 .0f , 0 .0f , 0 .0f );
748
-
749
- const Quatf q_sensor_rotation = attitude * q_sensor;
750
-
751
- const Vector3f rotated_sensor_vector = q_sensor_rotation.rotateVector (forward_vector);
752
-
753
- float sensor_dist_scale = rotated_sensor_vector.xy ().norm ();
754
- sensor_dist_scale = math::constrain (sensor_dist_scale, FLT_EPSILON, 1 .0f ); // limit it to the expected range.
755
- distance = distance * sensor_dist_scale;
747
+ const Quatf q_vehicle_sensor (Quatf (cosf (yaw / 2 .f ), 0 .f , 0 .f , sinf (yaw / 2 .f )));
748
+ const Quatf q_world_sensor = q_world_vehicle * q_vehicle_sensor;
749
+ const Vector3f forward (1 .f , 0 .f , 0 .f );
750
+ const Vector3f sensor_direction_in_world = q_world_sensor.rotateVector (forward);
751
+
752
+ float horizontal_projection_scale = sensor_direction_in_world.xy ().norm ();
753
+ horizontal_projection_scale = math::constrain (horizontal_projection_scale, FLT_EPSILON, 1 .0f );
754
+ distance *= horizontal_projection_scale;
756
755
}
757
756
758
757
uint8_t SF45LaserSerial::sf45_convert_angle (const int16_t yaw)
0 commit comments