Obstacle_distance: use only one increment in float directly

CollisionPrevention: rename a few variables to make the code more readable
This commit is contained in:
Martina Rivizzigno
2019-06-05 17:51:06 +02:00
committed by Beat Küng
parent d216b45202
commit 09bfb00c88
3 changed files with 29 additions and 29 deletions

View File

@@ -1677,9 +1677,17 @@ MavlinkReceiver::handle_message_obstacle_distance(mavlink_message_t *msg)
obstacle_distance.timestamp = hrt_absolute_time();
obstacle_distance.sensor_type = mavlink_obstacle_distance.sensor_type;
memcpy(obstacle_distance.distances, mavlink_obstacle_distance.distances, sizeof(obstacle_distance.distances));
obstacle_distance.increment = mavlink_obstacle_distance.increment;
if (mavlink_obstacle_distance.increment_f > 0.f) {
obstacle_distance.increment = mavlink_obstacle_distance.increment_f;
} else {
obstacle_distance.increment = (float)mavlink_obstacle_distance.increment;
}
obstacle_distance.min_distance = mavlink_obstacle_distance.min_distance;
obstacle_distance.max_distance = mavlink_obstacle_distance.max_distance;
obstacle_distance.angle_offset = mavlink_obstacle_distance.angle_offset;
if (_obstacle_distance_pub == nullptr) {
_obstacle_distance_pub = orb_advertise(ORB_ID(obstacle_distance), &obstacle_distance);