quadcopter.py 2.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879
  1. '''
  2. This is an example builder script that sets up a quadcopter in Morse to
  3. be driven by ArduPilot.
  4. The quadcopter has the basic set of sensors that ArduPilot needs
  5. To start the simulation use this:
  6. morse run quadcopter.py
  7. Then connect with ArduPilot like this:
  8. sim_vehicle.py --model morse --console --map
  9. This model assumes an X frame quadcopter, so you will need:
  10. FRAME_CLASS 1
  11. FRAME_TYPE 1
  12. '''
  13. from morse.builder import *
  14. # use the ATRV rover
  15. vehicle = Quadrotor()
  16. vehicle.properties(Object = True, Graspable = False, Label = "Vehicle")
  17. vehicle.translate(x=0.0, z=1.0)
  18. # add a camera
  19. camera = SemanticCamera(name="Camera")
  20. camera.translate(x=0.2, y=0.3, z=0.9)
  21. vehicle.append(camera)
  22. camera.properties(cam_far=800)
  23. camera.properties(Vertical_Flip=True)
  24. # we could optionally stream the video to a port
  25. #camera.add_stream('socket')
  26. # add sensors needed for ArduPilot operation to a vehicle
  27. pose = Pose()
  28. vehicle.append(pose)
  29. imu = IMU()
  30. vehicle.append(imu)
  31. gps = GPS()
  32. gps.alter('UTM')
  33. vehicle.append(gps)
  34. velocity = Velocity()
  35. vehicle.append(velocity)
  36. # create a compound sensor of all of the individual sensors and stream it
  37. all_sensors = CompoundSensor([imu, gps, velocity, pose])
  38. all_sensors.add_stream('socket')
  39. vehicle.append(all_sensors)
  40. # make the vehicle controllable via force and torque
  41. # this will be available on port 4000 by default
  42. engines = QuadrotorDynamicControl()
  43. vehicle.append(engines)
  44. engines.add_stream('socket')
  45. # this would allow us to control the vehicle with a keyboard
  46. # we don't enable it as it causes issues with sensor consistency
  47. #keyboard = Keyboard()
  48. #keyboard.properties(Speed=3.0)
  49. #vehicle.append(keyboard)
  50. # Environment. Run in fast mode which gives wire-frame view, but lowers
  51. # CPU load a lot
  52. env = Environment('land-1/trees', fastmode=True)
  53. env.set_camera_location([10.0, -10.0, 10.0])
  54. env.set_camera_rotation([1.0470, 0, 0.7854])
  55. env.select_display_camera(camera)
  56. env.set_camera_clip(clip_end=1000)
  57. # startup at CMAC. A location is needed for the magnetometer
  58. env.properties(longitude = 149.165230, latitude = -35.363261, altitude = 584.0)