Skip to content

Research quadrotor platform (software & hardware) developed at Stanford Multi-Robot Systems Lab

License

Notifications You must be signed in to change notification settings

StanfordMSL/msl_quad

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

msl_quad

Build Status Documentation Status

Quadrotor aerial robot developed at Multi-Robot Systems Lab.

This repository contains CAD design files, and code for low-level quadrotor controls and trajectory following through the mavros interface.

For high-level trajectory planning and generation, please refer to our QuadsManip repository.

Table of Contents

Dependencies

  • vrpn_client_ros: install with sudo apt-get install ros-<VERSION>-vrpn-client_ros
  • Eigen3

Demo Videos

cla

Related Papers

If you find our work useful in your research, please consider citing:

Hardware and Experiments

  • Z. Wang, R. Spica and M. Schwager, “Game Theoretic Motion Planning for Multi-Robot Racing,” In Proc. of the International Symposium on Distributed Autonomous Robotics Systems (DARS 18), October, 2018. [ PDF ]

Trajectory Generation

  • Z. Wang, S. Singh, M. Pavone and M. Schwager, “Cooperative Object Transport in 3D with Multiple Quadrotors using No Peer Communication,” In Proc. of the International Conference on Robotics and Automation (ICRA), pp. 1064-1071, 2018. [ PDF ]

Differential Flatness

  • D. Zhou, Z. Wang and M. Schwager, “Agile Coordination and Assistive Collision Avoidance for Quadrotor Swarms Using Virtual Structures,” IEEE Transactions on Robotics, vol. 34, no. 4, pp. 916-923, 2018. [ PDF ]

  • D. Zhou and M. Schwager, “Vector Field Following for Quadrotors using Differential Flatness,” In Proc. of the International Conference on Robotics and Automation (ICRA), pp. 6567-6572. 2014. [ PDF ]

Software Versions

  • px4 firmware: v1.7.3
  • mavros: 0.23 or later
  • mavlink: 2018.2.2 or later

Pixhawk Configuration

We use Pixhawk autopilot as the low level flight controller board. In order to use the motion capture for state estimation on Pixhawk, the following parameters must be modified through QGoundControl:

  • SYS_MC_EST_GROUP = ekf2
  • EKF2_AID_MASK = 24
  • EKF2_BARO_GATE = 0
  • EKF2_EVP_NOISE = 0.01
  • EKF2_EV_GATE = 500
  • EKF2_HGT_MODE = vision

The motion capture data should be streamed to Pixhawk through the mavros/vision_pose/pose ROS topic, which is configured in our launch file launch/quad_vrpn.launch by default.

Note: Under the PX4 version we use (v1.7.3), once these parameters are changed, you can no longer manually fly the quadrotor without streaming motion capture data to Pixhawk.

We need to configure baud rate to be 921600 (default is 57600) for serial communication between Pixhawk and the companion computer (Odroid XU4). If you use a Pixhawk variant with more than 1 serial port (e.g., Pixhawk 1, Pixracer), set SYS_COMPANION = 921600 and use TELEM 2 to connect to Odoird. If the Pixhawk only has 1 serial port (e.g., Pixfalcon, which is we are currently using), create a file etc/extras.txt on Pixhawk's SD card with the following two lines

mavlink stop-all
mavlink start -d /dev/ttyS1 -b 921600 -r 20000 -m onboard

which will change the baud rate of the only serial port (TELEM 1) upon boot up.

Note: If you use the SD card to change the baud rate, you need to temporarily unplug the SD card if you want to connect to QGroundControl via USB.

Simulation

  • requires frimware v1.9

  • add export PX4_FIRMWARE_PATH="{path_to_firmware}" source ${PX4_FIRMWARE_PATH}/Tools/setup_gazebo.bash ${PX4_FIRMWARE_PATH} ${PX4_FIRMWARE_PATH}/build/px4_sitl_default export ROS_PACKAGE_PATH=$ROS_PACKAGE_PATH:${PX4_FIRMWARE_PATH}:${PX4_FIRMWARE_PATH}/Tools/sitl_gazebo to your bash rc

  • run make px4_sitl_default gazebo

  • delete cached parameters .ros/eeprom/parameters

  • run roslaunch mslquad quad_sim.launch

Usage

Common

  • Start mavros and VRPN for mocap: roslaunch mslquad quad_vrpn.launch

  • May need to change vrpn_server_ip in launch/vrpn_track.launch to the ip address of the mocap machine.

Trajectory Following

  • A basic trajectory following controller is implemented in src/px4_base_controller.cpp.

    roslaunch mslquad default_controller.launch

  • The controller accepts trajectory from topic command/trajectory, which is of type MultiDOFJointTrajectory. It's important that the trajectory is updated at least 10Hz since the controller uses a simple lookahead strategy.

  • At the moment, the controller operates at a fixed height (only works for 2D trajectory). 3D trajectory is TODO.

Tests

  • Test position control:

    roslaunch mslquad pos_ctrl_test.launch

  • Test velocity control:

    roslaunch mslquad vel_ctrl_test.launch

  • Experimental: test direct motor control (se3 control). This requires custom PX4 firmware:

    roslaunch mslquad se3controller.launch

Contributing

  • Report bug or reqeust feature by opening issues on Github

  • Contribution is very welcome. Please fork the project and submit pull requests. New code will be reviewed before merging into the codebase.

  • Common functionality should be implemented in src/px4_base_controller.cpp. New controller should derive from the base controller, and override the controlLoop() function.