SITL: increase quad scanner range to 18m

Matches the value we send for Rover, which is useful until we can
reflect on the simulation to discover its maximum range
This commit is contained in:
Peter Barker 2021-01-03 17:48:56 +11:00 committed by Peter Barker
parent 2f5f55f680
commit 995f5d1dad
2 changed files with 2 additions and 2 deletions

View File

@ -622,7 +622,7 @@ void Morse::send_report(void)
packet.min_distance = 1;
// the simulated rangefinder has an imposed 18m limit in
// e.g. rover_scanner.py
packet.max_distance = 1800;
packet.max_distance = 5000;
packet.sensor_type = MAV_DISTANCE_SENSOR_LASER;
packet.increment = 0; // use increment_f

View File

@ -53,7 +53,7 @@ scan = Hokuyo()
scan.translate(x=0.0, z=1)
vehicle.append(scan)
scan.properties(Visible_arc = True)
scan.properties(laser_range = 5.0)
scan.properties(laser_range = 18.0)
scan.properties(resolution = 5.0)
scan.properties(scan_window = 360.0)
scan.create_laser_arc()