ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question

Revision history [back]

There are several possible reasons for the symptoms you describe:

  • At least one of the required Gazebo plugins has not been loaded for some reason or could not parse its parameters from the URDF description. You should check the console output if there are error messages that could serve as a starting point. Also check that /cmd_vel is published correctly using rostopic echo /cmd_vel and that gazebo subscribes to this topic rostopic info /cmd_vel.

  • There might be NaN values for some reason in a message the controller plugin uses to calculate the required thrust and torques. You can check this easily with rostopic echo. Using the default configuration, the relevant topics are /ground_truth/state and /raw_imu. (Note: There was a bug introduced in revision 811 and resolved in revision 814 that caused the IMU plugin in hector_gazebo_plugins to publish NaN values for the first timestep, which are fed through to the torque output due to the integrators in the controller.)

  • Make sure to NOT use the propulsion model plugin in package hector_quadrotor_controller as for now. This plugin requires an installation of Matlab with Matlab Coder to compile successfully, and when the binary is found, the cmake scripts in hector_quadrotor_gazebo will add it to the quadrotor URDF instead of the simple controller plugin. The propulsion plugin requires motor voltages as input and does not react on /cmd_vel directly. We bridge this gap by running our onboard software running in Orocos RTT with ROS integration, which is not (yet) available in the repo. When the propulsion model is enabled without a running controller, the quadrotor will just fall down and stay on the ground. Without the plugin it is not really possible to touch down, as the simple controller will always produce a certain thrust required to compensate gravity. When no commands are received, the quadrotor will hover a couple of centimeters above ground and slowly drifts away due to IMU noise and numerical inaccuracies.

    You can disable the propulsion plugin with the command

    roscd hector_quadrotor_gazebo/build && cmake . -DUSE_PROPULSION_MODEL=OFF
    
  • If you are using ROS fuerte, you should first try to install hector_quadrotor from the package repository instead of doing a source installation:

    sudo apt-get install ros-fuerte-hector-quadrotor
    

    We expect to release a new version of the stack for fuerte and groovy as soon as some problems with the new Gazebo version (e.g. spawning at the wrong position) have been resolved.

    When checking out the SVN version directly, make sure to use the /trunk version to also get the latest updates. Unfortunately the wiki page is still showing an outdated URL in /branches/fuerte for ROS fuerte (see this question).