roll_pitch_yawrate_thrust_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_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H
22 #define ROTORS_CONTROL_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H
23 
24 #include <mav_msgs/conversions.h>
26 
27 #include "rotors_control/common.h"
29 
30 namespace rotors_control {
31 
32 // Default values for the roll pitch yawrate thrust controller and the Asctec Firefly.
33 static const Eigen::Vector3d kDefaultAttitudeGain = Eigen::Vector3d(3, 3, 0.035);
34 static const Eigen::Vector3d kDefaultAngularRateGain = Eigen::Vector3d(0.52, 0.52, 0.025);
35 
37  public:
38  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40  : attitude_gain_(kDefaultAttitudeGain),
41  angular_rate_gain_(kDefaultAngularRateGain) {
43  }
44 
45  Eigen::Matrix4Xd allocation_matrix_;
46  Eigen::Vector3d attitude_gain_;
47  Eigen::Vector3d angular_rate_gain_;
49 };
50 
52  public:
55  void InitializeParameters();
56  void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const;
57 
58  void SetOdometry(const EigenOdometry& odometry);
59  void SetRollPitchYawrateThrust(
60  const mav_msgs::EigenRollPitchYawrateThrust& roll_pitch_yawrate_thrust);
61 
64 
65  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
66  private:
69 
70  Eigen::Vector3d normalized_attitude_gain_;
73 
76 
77  void ComputeDesiredAngularAcc(Eigen::Vector3d* angular_acceleration) const;
78 };
79 }
80 
81 #endif // ROTORS_CONTROL_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H
static const Eigen::Vector3d kDefaultAngularRateGain
static const Eigen::Vector3d kDefaultAttitudeGain
RollPitchYawrateThrustControllerParameters controller_parameters_
void calculateAllocationMatrix(const RotorConfiguration &rotor_configuration, Eigen::Matrix4Xd *allocation_matrix)
Definition: common.h:79


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