mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: TeraRangerTower uses modified Boundary_3D interface
This commit is contained in:
parent
d4a6ebd273
commit
5c9a65cff6
|
@ -93,14 +93,13 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
|||
void AP_Proximity_TeraRangerTower::update_sector_data(int16_t angle_deg, uint16_t distance_cm)
|
||||
{
|
||||
// Get location on 3-D boundary based on angle to the object
|
||||
const boundary_location bnd_loc = boundary.get_sector(angle_deg);
|
||||
boundary.reset_sector(bnd_loc);
|
||||
const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg);
|
||||
if (distance_cm != 0xffff) {
|
||||
boundary.set_attributes(bnd_loc, angle_deg, ((float) distance_cm) / 1000);
|
||||
boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000);
|
||||
// update OA database
|
||||
database_push(angle_deg, ((float) distance_cm) / 1000);
|
||||
} else {
|
||||
boundary.reset_face(face);
|
||||
}
|
||||
_last_distance_received_ms = AP_HAL::millis();
|
||||
// update boundary used for avoidance
|
||||
boundary.update_boundary(bnd_loc);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue