Package Summary
hector_quadrotor_controller provides plugins for a quadrotor controller in gazebo. hector_quadrotor_aerodynamics simulates the quadrotor's motor, propeller and drag dynamics, given the four input voltages and the wind vector. hector_quadrotor_simple_controller is a simple controller allowing to command the quadrotor's velocity using a geometry_msgs/Twist message for teleoperation.
- Author: Johannes Meyer and Alexander Sendobry
- License: BSD
- Source: svn https://tu-darmstadt-ros-pkg.googlecode.com/svn/branches/electric/hector_quadrotor
Package Summary
hector_quadrotor_controller provides plugins for a quadrotor controller in gazebo. hector_quadrotor_aerodynamics simulates the quadrotor's motor, propeller and drag dynamics, given the four input voltages and the wind vector.
- Author: Johannes Meyer and Alexander Sendobry
- License: BSD
- Source: git https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor.git
Package Summary
hector_quadrotor_controller provides plugins for a quadrotor controller in gazebo. hector_quadrotor_aerodynamics simulates the quadrotor's motor, propeller and drag dynamics, given the four input voltages and the wind vector.
- Author: Johannes Meyer and Alexander Sendobry
- License: BSD
- Source: git https://github.com/tu-darmstadt-ros-pkg/hector_quadrotor.git
Contents
Available Plugins
Simple Quadrotor Controller
The simple quadrotor plugin is a generic controller for quadrotors that enables teleoperated flying in Gazebo. PID controllers are used to control the velocities and yaw rate by calculating the necessary forces and torques acting on the body. It is called "simple controller" as it makes some assumptions that usually hold for quadrotors during hovering and non-aerobatic maneuvers.
The controller uses a cascade of two PID controllers for the horizontal movement and two separate PID controllers for the yaw rate and vertical velocity.
The plugin currently does not provide position, heading or altitude control. You can implement your own position controller on top of it.
Subscribed Topics
cmd_vel (geometry_msgs/Twist):
- The desired velocities and yaw rate of the quadrotor. The angular velocities around x- and y-axis are ignored.
XML Parameters
updateRate (double): update rate of the controller in Hz (should always be zero = simulation rate)
robotNamespace (string): namespace prefix for topic names
bodyName (string): name of the quadrotor body link in Gazebo
topicName (string): name of the twist command input topic (defaults to cmd_vel)
imuTopic (string): name of the imu topic (sensor_msgs/Imu) to be subscribed and used as current orientation and angular rates source. If empty, ground truth information from Gazebo is used for control (default).
stateTopic (string): name of the state topic (nav_msgs/Odometry) to be subscribed and used as current velocity and acceleration source. If empty, ground truth information from Gazebo is used for control (default).
maxForce (double): if greater than 0, upper limit of total thrust along the z-axis (defaults to unlimited)
Controller parameters
You can modify the dynamics of the controller by modifying the control parameters. See sample launch file in quadrotor_simple_controller.urdf.xacro for details.
Quadrotor Aerodynamics
The aerodynamics plugin simulates the propulsion system (moments and forces generated by the rotation of the propellers) and drag. It takes the motor voltages as input.
Subscribed Topics
motor_pwm (hector_uav_msgs/MotorPWM):
- The commanded motor voltages for the four motors. The voltage is given as pulse width in the range of 0 to 255 (full battery voltage).
wind (geometry_msgs/Vector3):
- You can specify a wind vector using this topic, which is substracted from the quadrotor's base velocity to calculate the drag forces.
Published Topics
motor_status (hector_uav_msgs/MotorStatus):
- The simulated motor speeds and currents.
wrench_out (geometry_msgs/Wrench):
- The resulting forces and moments generated by the propulsion system (for debugging purposes mainly).
XML Parameters
updateRate (double): update rate of the controller in Hz (should always be zero = simulation rate)
controlRate (double): update rate of the controller rate in Hz. If greater than 0, the simulation will be throttled if new motor voltages arrive slower than this rate.
controlDelay (double): tolerance for the delay of the voltage timestamps compared to the simulation time
robotNamespace (string): namespace prefix for topic names
bodyName (string): name of the quadrotor body link in Gazebo
voltageTopicName (string): name of the motor voltage input topic (defaults to motor_pwm)
statusTopic (string): name of the motor status topic (defaults to motor_status)
wrenchTopic (string): name of the wrench output topic (defaults to wrench_out)
ROS Parameters
A bunch of parameters that describe the quadrotor model are loaded from the ROS parameter server during plugin initialization.
Matlab Compilation
The differential equations that describe the quadrotor system are implemented as Matlab scripts and compiled to C libraries using the Matlab Coder. You need a version of Matlab installed on your computer and available in the system path to compile this plugin.