Skip to content

Commit defccfa

Browse files
authored
Collision Prevention: Scale obstacle distance with vehicle attitude for varying sensor orientations (#24107)
1 parent b765769 commit defccfa

File tree

2 files changed

+18
-4
lines changed

2 files changed

+18
-4
lines changed

src/lib/collision_prevention/CollisionPrevention.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -400,11 +400,15 @@ CollisionPrevention::_addDistanceSensorData(distance_sensor_s &distance_sensor,
400400
int lower_bound = (int)round((sensor_yaw_body_deg - math::degrees(distance_sensor.h_fov / 2.0f)) / BIN_SIZE);
401401
int upper_bound = (int)round((sensor_yaw_body_deg + math::degrees(distance_sensor.h_fov / 2.0f)) / BIN_SIZE);
402402

403+
const Quatf q_sensor(Quatf(cosf(sensor_yaw_body_rad / 2.f), 0.f, 0.f, sinf(sensor_yaw_body_rad / 2.f)));
403404

404-
// rotate vehicle attitude into the sensor body frame
405-
Quatf attitude_sensor_frame = vehicle_attitude;
406-
attitude_sensor_frame.rotate(Vector3f(0.f, 0.f, sensor_yaw_body_rad));
407-
float sensor_dist_scale = cosf(Eulerf(attitude_sensor_frame).theta()); // verify
405+
const Vector3f forward_vector(1.0f, 0.0f, 0.0f);
406+
407+
const Quatf q_sensor_rotation = vehicle_attitude * q_sensor;
408+
409+
const Vector3f rotated_sensor_vector = q_sensor_rotation.rotateVector(forward_vector);
410+
411+
const float sensor_dist_scale = rotated_sensor_vector.xy().norm();
408412

409413
if (distance_reading < distance_sensor.max_distance) {
410414
distance_reading = distance_reading * sensor_dist_scale;

src/modules/simulation/gz_bridge/GZBridge.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -800,7 +800,10 @@ void GZBridge::laserScantoLidarSensorCallback(const gz::msgs::LaserScan &scan)
800800
pose_orientation.y(),
801801
pose_orientation.z());
802802

803+
const gz::math::Quaterniond q_left(0.7071068, 0, 0, -0.7071068);
804+
803805
const gz::math::Quaterniond q_front(0.7071068, 0.7071068, 0, 0);
806+
804807
const gz::math::Quaterniond q_down(0, 1, 0, 0);
805808

806809
if (q_sensor.Equal(q_front, 0.03)) {
@@ -809,8 +812,15 @@ void GZBridge::laserScantoLidarSensorCallback(const gz::msgs::LaserScan &scan)
809812
} else if (q_sensor.Equal(q_down, 0.03)) {
810813
distance_sensor.orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING;
811814

815+
} else if (q_sensor.Equal(q_left, 0.03)) {
816+
distance_sensor.orientation = distance_sensor_s::ROTATION_LEFT_FACING;
817+
812818
} else {
813819
distance_sensor.orientation = distance_sensor_s::ROTATION_CUSTOM;
820+
distance_sensor.q[0] = q_sensor.W();
821+
distance_sensor.q[1] = q_sensor.X();
822+
distance_sensor.q[2] = q_sensor.Y();
823+
distance_sensor.q[3] = q_sensor.Z();
814824
}
815825

816826
_distance_sensor_pub.publish(distance_sensor);

0 commit comments

Comments
 (0)