rover_scanner.py 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495
  1. '''
  2. This is an example builder script that sets up a rover in Morse to
  3. be driven by ArduPilot.
  4. The rover has the basic set of sensors that ArduPilot needs
  5. To start the simulation use this:
  6. morse run rover.py
  7. Then connect with ArduPilot like this:
  8. sim_vehicle.py --model morse --console --map
  9. This model assumes you will setup a skid-steering rover with left throttle on
  10. channel 1 and right throttle on channel 2, which means you need to set:
  11. SERVO1_FUNCTION 73
  12. SERVO3_FUNCTION 74
  13. '''
  14. from morse.builder import *
  15. # use the ATRV rover
  16. vehicle = ATRV()
  17. vehicle.properties(Object = True, Graspable = False, Label = "Vehicle")
  18. vehicle.translate(x=0.0, z=0.0)
  19. vehicle.rotate(z=math.pi)
  20. # add a camera
  21. camera = SemanticCamera(name="Camera")
  22. camera.translate(x=0.2, y=0.3, z=0.9)
  23. vehicle.append(camera)
  24. camera.properties(cam_far=800)
  25. camera.properties(Vertical_Flip=False)
  26. camera.rotate(z=math.pi)
  27. # we could optionally stream the video to a port
  28. #camera.add_stream('socket')
  29. # add sensors needed for ArduPilot operation to a vehicle
  30. pose = Pose()
  31. vehicle.append(pose)
  32. imu = IMU()
  33. vehicle.append(imu)
  34. gps = GPS()
  35. gps.alter('UTM')
  36. vehicle.append(gps)
  37. velocity = Velocity()
  38. vehicle.append(velocity)
  39. # add a 360 degree laser scanner, sitting 1m above the rover
  40. # this is setup to be similar to the RPLidarA2
  41. scan = Hokuyo()
  42. scan.translate(x=0.0, z=1.0)
  43. vehicle.append(scan)
  44. scan.properties(Visible_arc = True)
  45. scan.properties(laser_range = 18.0)
  46. scan.properties(resolution = 5.0)
  47. scan.properties(scan_window = 360.0)
  48. scan.create_laser_arc()
  49. # create a compound sensor of all of the individual sensors and stream it
  50. all_sensors = CompoundSensor([imu, gps, velocity, pose, scan])
  51. all_sensors.add_stream('socket')
  52. vehicle.append(all_sensors)
  53. # make the vehicle controllable with speed and angular velocity
  54. # this will be available on port 60001 by default
  55. # an example command is:
  56. # {"v":2, "w":1}
  57. # which is 2m/s fwd, and rotating left at 1 radian/second
  58. motion = MotionVW()
  59. vehicle.append(motion)
  60. motion.add_stream('socket')
  61. # this would allow us to control the vehicle with a keyboard
  62. # we don't enable it as it causes issues with sensor consistency
  63. #keyboard = Keyboard()
  64. #keyboard.properties(Speed=3.0)
  65. #vehicle.append(keyboard)
  66. # Environment
  67. env = Environment('indoors-1/boxes', fastmode=False)
  68. env.set_camera_location([10.0, -10.0, 10.0])
  69. env.set_camera_rotation([1.0470, 0, 0.7854])
  70. env.select_display_camera(camera)
  71. env.set_camera_clip(clip_end=1000)
  72. # startup at CMAC. A location is needed for the magnetometer
  73. env.properties(longitude = 149.165230, latitude = -35.363261, altitude = 584.0)