mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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:
parent
2f5f55f680
commit
995f5d1dad
@ -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
|
||||
|
||||
|
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user