attitude_controller.h
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
3  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
4  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
5  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
6  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
7  *
8  * Licensed under the Apache License, Version 2.0 (the "License");
9  * you may not use this file except in compliance with the License.
10  * You may obtain a copy of the License at
11  *
12  * http://www.apache.org/licenses/LICENSE-2.0
13 
14  * Unless required by applicable law or agreed to in writing, software
15  * distributed under the License is distributed on an "AS IS" BASIS,
16  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
17  * See the License for the specific language governing permissions and
18  * limitations under the License.
19  */
20 
21 #ifndef ROTORS_CONTROL_ATTITUDE_CONTROLLER_H
22 #define ROTORS_CONTROL_ATTITUDE_CONTROLLER_H
23 
24 #include "rotors_control/controller_base.h"
25 #include "rotors_control/controller_factory.h"
26 
27 class AttitudeController : public ControllerBase {
28  public:
30  virtual ~AttitudeController();
31  virtual void InitializeParams();
32  virtual std::shared_ptr<ControllerBase> Clone();
33  virtual void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const;
34 
35  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
36  private:
37  Eigen::Matrix4Xd allocation_matrix_;
39  Eigen::Vector3d gain_attitude_;
40  Eigen::Vector3d gain_angular_rate_;
41  Eigen::Matrix3d inertia_matrix_;
42 
43  double mass_;
44  const double gravity_;
45 
46  void ComputeDesiredAngularAcc(Eigen::Vector3d * angular_acceleration) const;
47 
48 };
49 
50 #endif // ROTORS_CONTROL_ATTITUDE_CONTROLLER_H
virtual std::shared_ptr< ControllerBase > Clone()
Eigen::Matrix3d inertia_matrix_
Eigen::Matrix4Xd allocation_matrix_
Eigen::Vector3d gain_attitude_
Eigen::Vector3d gain_angular_rate_
Eigen::MatrixX4d angular_acc_to_rotor_velocities_
void ComputeDesiredAngularAcc(Eigen::Vector3d *angular_acceleration) const
virtual void InitializeParams()
virtual void CalculateRotorVelocities(Eigen::VectorXd *rotor_velocities) const


rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Mon Feb 28 2022 23:38:55