Ignition Gazebo

API Reference

3.5.0
MulticopterVelocityControl Class Reference

This is a velocity controller for multicopters that allows control over the linear velocity and the yaw angular velocity of the vehicle. The velocities are expressed in the body frame of the vehicle. A vehicle with at least 4 rotors is required for the controller to function. More...

#include <MulticopterVelocityControl.hh>

Public Member Functions

 MulticopterVelocityControl ()=default
 Constructor. More...
 
void Configure (const Entity &_entity, const std::shared_ptr< const sdf::Element > &_sdf, EntityComponentManager &_ecm, EventManager &_eventMgr) override
 Configure the system. More...
 
void PreUpdate (const UpdateInfo &_info, EntityComponentManager &_ecm) override
 
- Public Member Functions inherited from System
 System ()
 Constructor. More...
 
virtual ~System ()
 Destructor. More...
 

Detailed Description

This is a velocity controller for multicopters that allows control over the linear velocity and the yaw angular velocity of the vehicle. The velocities are expressed in the body frame of the vehicle. A vehicle with at least 4 rotors is required for the controller to function.

Note that this system only computes the necessary rotor velocities and updates the Actuators component on the model entity. To actually convert these velocities to thrust, this system requires the MulticopterMotorModel system on each rotor. Note also that only one MulticopterVelocityControl system is allowed per model.

This system is inspired by the LeePositionController from RotorS https://github.com/ethz-asl/rotors_simulator/blob/master/rotors_control/include/rotors_control/lee_position_controller.h Instead of subscribing to odometry messages, this system uses ground truth values of orientation, linear velocity and angular velocity from simulation. As such it is not designed to work with user supplied state estimators. Instead, the system allows noise to be added to velocity values to simulate the behavior of state estimators.

Main differences/additions include:

  • Only controls velocity. Velocity estimates are obtained from simulation ground truth, but noise can be added to simulate realistic estimators.
  • Automatic calculation of rotor angle and arm length
  • Automatic calculation of vehicle mass and inertia
  • Handling of non-orthogonal rotor axis
  • Maximum acceleration limit
  • Can be enabled/disabled at runtime.

Parameters

The following parameters are used by the system

robotNamespace: All ign-transport topics subscribed to and published by the system will be prefixed by this string. This is a required parameter.

commandSubTopic: The system subscribes to this topic to receive twist commands. The default value is "cmd_vel".

enableSubTopic: Topic to enable or disable the system. If false, the controller sends a zero rotor velocity command once and gets disabled. If the vehicle is in the air, disabling the controller will cause it to fall. If true, the controller becomes enabled and waits for a twist message. The default value is "enable".

comLinkName: The link associated with the center of mass of the vehicle. That is, the origin of the center of mass may not be on this link, but this link and the center of mass frame have a fixed transform. Almost always this should be the base_link of the vehicle. This is a required parameter.

velocityGain (x, y, z): Proportional gain on linear velocity. attitudeGain (roll, pitch, yaw): Proportional gain on attitude. This parameter is scaled by the inverse of the inertia matrix so two vehicles with different inertial characteristics may have the same gain if other parameters, such as the forceConstant, are kept the same. This is a required parameter.

angularRateGain (roll, pitch, yaw): Proportional gain on angular velocity. Even though only the yaw angle velocity is controlled, proper gain values for roll and pitch velocities must be specified. This parameter is scaled by the inverse of the inertia matrix so two vehicles with different inertial characteristics may have the same gain if other parameters, such as the forceConstant, are kept the same. This is a required parameter.

maxLinearAcceleration (x, y, z): Maximum limit on linear acceleration. The default value is DBL_MAX.

maximumLinearVelocity (x, y, z): Maximum commanded linear velocity. The default value is DBL_MAX. maximumAngularVelocity (roll, pitch, yaw): Maximum commanded angular velocity. The default value is DBL_MAX.

linearVelocityNoiseMean (x, y, z): Mean of Gaussian noise on linear velocity values obtained from simulation. The default value is (0, 0, 0).

linearVelocityNoiseStdDev (x, y, z): Standard deviation of Gaussian noise on linear values obtained from simulation. A value of 0 implies noise is NOT applied to the component. The default value is (0, 0, 0).

angularVelocityNoiseMean (roll, pitch, yaw): Mean of Gaussian noise on angular velocity values obtained from simulation. The default value is (0, 0, 0).

angularVelocityNoiseStdDev (roll, pitch, yaw): Standard deviation of gaussian noise on angular velocity values obtained from simulation. A value of 0 implies noise is NOT applied to the component. The default value is (0, 0, 0).

rotorConfiguration: This contains a list of <rotor> elements for each rotor in the vehicle. This is a required parameter.

rotor: Contains information about a rotor in the vehicle. All the elements of <rotor> are required parameters.

jointName: The name of the joint associated with this rotor.

forceConstant: A constant that multiplies with the square of the rotor's velocity to compute its thrust.

momentConstant: A constant the multiplies with the rotor's thrust to compute its moment.

direction: Direction of rotation of the rotor. +1 is counterclockwise and -1 is clockwise.

Examples

See examples/worlds/quadcopter.sdf for a demonstration.

Constructor & Destructor Documentation

◆ MulticopterVelocityControl()

Constructor.

Member Function Documentation

◆ Configure()

void Configure ( const Entity _entity,
const std::shared_ptr< const sdf::Element > &  _sdf,
EntityComponentManager _ecm,
EventManager _eventMgr 
)
overridevirtual

Configure the system.

Parameters
[in]_entityThe entity this plugin is attached to.
[in]_sdfThe SDF Element associated with this system plugin.
[in]_ecmThe EntityComponentManager of the given simulation instance.
[in]_eventMgrThe EventManager of the given simulation instance.

Implements ISystemConfigure.

◆ PreUpdate()

void PreUpdate ( const UpdateInfo _info,
EntityComponentManager _ecm 
)
overridevirtual

Implements ISystemPreUpdate.


The documentation for this class was generated from the following file: