|
38 | 38 | #include <termios.h>
|
39 | 39 | #include <lib/crc/crc.h>
|
40 | 40 | #include <lib/mathlib/mathlib.h>
|
| 41 | +#include <matrix/matrix/math.hpp> |
41 | 42 |
|
42 | 43 | #include <float.h>
|
43 | 44 |
|
44 | 45 | using namespace time_literals;
|
| 46 | +using matrix::Quatf; |
| 47 | +using matrix::Vector3f; |
45 | 48 |
|
46 | 49 | /* Configuration Constants */
|
47 | 50 |
|
@@ -649,11 +652,22 @@ void SF45LaserSerial::sf45_process_replies(float *distance_m)
|
649 | 652 | PX4_DEBUG("scaled_yaw: \t %d, \t current_bin: \t %d, \t distance: \t %8.4f\n", scaled_yaw, current_bin,
|
650 | 653 | (double)*distance_m);
|
651 | 654 |
|
| 655 | + if (_vehicle_attitude_sub.updated()) { |
| 656 | + vehicle_attitude_s vehicle_attitude; |
| 657 | + |
| 658 | + if (_vehicle_attitude_sub.copy(&vehicle_attitude)) { |
| 659 | + _vehicle_attitude = Quatf(vehicle_attitude.q); |
| 660 | + } |
| 661 | + } |
| 662 | + |
| 663 | + _scale_dist(*distance_m, scaled_yaw, _vehicle_attitude); |
| 664 | + |
652 | 665 | if (_current_bin_dist > _obstacle_distance.max_distance) {
|
653 | 666 | _current_bin_dist = _obstacle_distance.max_distance + 1; // As per ObstacleDistance.msg definition
|
654 | 667 | }
|
655 | 668 |
|
656 | 669 | hrt_abstime now = hrt_absolute_time();
|
| 670 | + |
657 | 671 | _handle_missed_bins(current_bin, _previous_bin, _current_bin_dist, now);
|
658 | 672 |
|
659 | 673 | _publish_obstacle_msg(now);
|
@@ -727,6 +741,20 @@ void SF45LaserSerial::_handle_missed_bins(uint8_t current_bin, uint8_t previous_
|
727 | 741 | }
|
728 | 742 | }
|
729 | 743 | }
|
| 744 | +void SF45LaserSerial::_scale_dist(float &distance, const int16_t &yaw, const matrix::Quatf &attitude) |
| 745 | +{ |
| 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; |
| 756 | +} |
| 757 | + |
730 | 758 | uint8_t SF45LaserSerial::sf45_convert_angle(const int16_t yaw)
|
731 | 759 | {
|
732 | 760 | uint8_t mapped_sector = 0;
|
|
0 commit comments