plane_quad.sh 910 B

123456789101112131415161718192021222324252627282930313233343536
  1. #!/bin/bash
  2. # a quad following a plane
  3. # assume we start the script from the root directory
  4. ROOTDIR=$PWD
  5. COPTER=$ROOTDIR/build/sitl/bin/arducopter
  6. PLANE=$ROOTDIR/build/sitl/bin/arduplane
  7. [ -x "$COPTER" -a -x "$PLANE" ] || {
  8. ./waf configure --board sitl
  9. ./waf plane copter
  10. }
  11. # setup for either TCP or multicast
  12. #UARTA="tcp:0"
  13. UARTA="mcast:"
  14. PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/plane.parm"
  15. COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm"
  16. mkdir -p swarm/plane swarm/copter
  17. (cd swarm/plane && $PLANE --model plane --uartA $UARTA --defaults $PLANE_DEFAULTS) &
  18. # create default parameter file for the follower
  19. cat <<EOF > swarm/copter/follow.parm
  20. SYSID_THISMAV 2
  21. FOLL_ENABLE 1
  22. FOLL_OFS_X -5
  23. FOLL_OFS_TYPE 1
  24. FOLL_SYSID 1
  25. FOLL_DIST_MAX 1000
  26. EOF
  27. (cd swarm/copter && $COPTER --model quad --uartA $UARTA --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) &
  28. wait