Ignition Gazebo

API Reference

6.9.0
LeeVelocityController.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2019 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 
18 #ifndef IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_
19 #define IGNITION_GAZEBO_SYSTEMS_MULTICOPTER_CONTROL_LEEVELOCITYCONTROLLER_HH_
20 
21 #include <Eigen/Geometry>
22 #include <memory>
23 #include "ignition/gazebo/config.hh"
24 
25 #include "Common.hh"
26 #include "LeeVelocityController.hh"
27 
28 namespace ignition
29 {
30 namespace gazebo
31 {
32 // Inline bracket to help doxygen filtering.
33 inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
34 namespace systems
35 {
36 namespace multicopter_control
37 {
41  {
42  Eigen::Vector3d velocityGain;
43  Eigen::Vector3d attitudeGain;
44  Eigen::Vector3d angularRateGain;
45  Eigen::Vector3d maxLinearAcceleration;
46  };
47 
53  {
59  public: static std::unique_ptr<LeeVelocityController> MakeController(
60  const LeeVelocityControllerParameters &_controllerParams,
61  const VehicleParameters &_vehicleParams);
62 
69  public: void CalculateRotorVelocities(
70  const FrameData &_frameData,
71  const EigenTwist &_cmdVel,
72  Eigen::VectorXd &_rotorVelocities) const;
73 
76  private: LeeVelocityController() = default;
77 
80  private: Eigen::Vector3d ComputeDesiredAcceleration(
81  const FrameData &_frameData, const EigenTwist &_cmdVel) const;
82 
85  private: Eigen::Vector3d ComputeDesiredAngularAcc(
86  const FrameData &_frameData, const EigenTwist &_cmdVel,
87  const Eigen::Vector3d &_acceleration) const;
88 
91  private: bool InitializeParameters();
92 
94  private: LeeVelocityControllerParameters controllerParameters;
95 
97  private: VehicleParameters vehicleParameters;
98 
100  private: Eigen::Vector3d normalizedAttitudeGain;
101 
103  private: Eigen::Vector3d normalizedAngularRateGain;
104 
107  private: Eigen::MatrixX4d angularAccToRotorVelocities;
108  };
109 } // namespace multicopter_control
110 } // namespace systems
111 } // namespace IGNITION_GAZEBO_VERSION_NAMESPACE
112 } // namespace gazebo
113 } // namespace ignition
114 
115 #endif
Eigen::Vector3d angularRateGain
Definition: LeeVelocityController.hh:44
Frame data of a link including its pose and linear velocity in world frame as well as its angular vel...
Definition: Common.hh:52
Eigen::Vector3d attitudeGain
Definition: LeeVelocityController.hh:43
Eigen::Vector3d velocityGain
Definition: LeeVelocityController.hh:42
Eigen::Vector3d maxLinearAcceleration
Definition: LeeVelocityController.hh:45
Data structure containing various parameters for the Lee velocity controller.
Definition: LeeVelocityController.hh:40
STL class.
A struct that holds properties of the vehicle such as mass, inertia and rotor configuration. Gravity is also included even though it&#39;s not a parameter unique to the vehicle.
Definition: Parameters.hh:68
Struct containing linear and angular velocities.
Definition: Common.hh:44
This library is part of the Ignition Robotics project.