attitude_controller_samy.cpp
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 
22 
23 #include <iostream>
24 
26  : gravity_(9.81),
27  mass_(1.56779) {
28 }
29 
31 }
32 
33 std::shared_ptr<ControllerBase> AttitudeControllerSamy::Clone() {
34  std::shared_ptr<ControllerBase> controller(new AttitudeControllerSamy);
35  return controller;
36 }
37 
39  gain_attitude_(0) = 3; //4
40  gain_attitude_(1) = 3; //4
41  gain_attitude_(2) = 0.035;
42 
43  gain_angular_rate_(0) = 0.52;//0.6;
44  gain_angular_rate_(1) = 0.52;//0.6;
45  gain_angular_rate_(2) = 0.025;
46 
47  amount_rotors_ = 6;
48  allocation_matrix_.resize(4,amount_rotors_);
49  allocation_matrix_ << sin(M_PI/6), 1, sin(M_PI/6), -sin(M_PI/6), -1, -sin(M_PI/6),
50  -cos(M_PI/6), 0, cos(M_PI/6), cos(M_PI/6), 0, -cos(M_PI/6),
51  -1, 1, -1, 1, -1, 1,
52  1, 1, 1, 1, 1, 1;
53 
54  inertia_matrix_<< 0.0347563, 0, 0,
55  0, 0.0458929, 0,
56  0, 0, 0.0977;
57 
58  // to make the tuning independent of the inertia matrix we divide here
59  gain_attitude_ = gain_attitude_.transpose() * inertia_matrix_.inverse();
60 
61  // to make the tuning independent of the inertia matrix we divide here
62  gain_angular_rate_ = gain_angular_rate_.transpose() * inertia_matrix_.inverse();
63 
64  const double rotor_force_constant = 0.00000854858; //F_i = k_n * rotor_velocity_i^2
65  const double rotor_moment_constant = 0.016; // M_i = k_m * F_i
66 
67  angular_acc_to_rotor_velocities_.resize(amount_rotors_, 4);
68  const double arm_length = 0.215;
69 
70  Eigen::Matrix4d K;
71  K.setZero();
72  K(0, 0) = arm_length * rotor_force_constant;
73  K(1, 1) = arm_length * rotor_force_constant;
74  K(2, 2) = rotor_force_constant * rotor_moment_constant;
75  K(3, 3) = rotor_force_constant;
76 
77  Eigen::Matrix4d I;
78  I.setZero();
79  I.block<3, 3>(0, 0) = inertia_matrix_;
80  I(3, 3) = 1;
82  * (allocation_matrix_ * allocation_matrix_.transpose()).inverse() * K.inverse() * I;
83  initialized_params_ = true;
84 }
85 
86 void AttitudeControllerSamy::CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const {
87  assert(rotor_velocities);
88  assert(initialized_params_);
89 
90  rotor_velocities->resize(amount_rotors_);
91 
92  Eigen::Vector3d angular_acceleration;
93  ComputeDesiredAngularAcc(&angular_acceleration);
94 
95  Eigen::Vector4d angular_acceleration_thrust;
96  angular_acceleration_thrust.block<3, 1>(0, 0) = angular_acceleration;
97  angular_acceleration_thrust(3) = control_attitude_thrust_reference_(3);
98 
99  *rotor_velocities = angular_acc_to_rotor_velocities_ * angular_acceleration_thrust;
100  *rotor_velocities = rotor_velocities->cwiseMax(Eigen::VectorXd::Ones(rotor_velocities->rows()));
101  *rotor_velocities = rotor_velocities->cwiseSqrt();
102 }
103 
104 // Control of complex maneuvers for a quadrotor UAV using geometric methods on SE(3)
105 void AttitudeControllerSamy::ComputeDesiredAngularAcc(Eigen::Vector3d* angular_acceleration) const {
106  assert(angular_acceleration);
107 
108  Eigen::Matrix3d R = attitude_.toRotationMatrix();
109 
110  // get desired rotation matrix
111  Eigen::Matrix3d R_des;
112  double yaw = atan2(R(1, 0), R(0, 0));
113  R_des = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ()) // yaw
114  * Eigen::AngleAxisd(control_attitude_thrust_reference_(0), Eigen::Vector3d::UnitX()) // roll
115  * Eigen::AngleAxisd(control_attitude_thrust_reference_(1), Eigen::Vector3d::UnitY()); // pitch
116 
117  Eigen::Vector3d b3_des = R.transpose() * R_des.col(2);
118  Eigen::Vector3d angle_error = b3_des.cross(Eigen::Vector3d::UnitZ());
119 
120  Eigen::Vector3d angular_rate_des(Eigen::Vector3d::Zero());
121  angular_rate_des[2] = control_attitude_thrust_reference_(2);
122 
123  Eigen::Vector3d angular_rate_error = angular_rate_ - R_des.transpose() * R * angular_rate_des;
124 
125  *angular_acceleration = -1 * angle_error.cwiseProduct(gain_attitude_)
126  - angular_rate_error.cwiseProduct(gain_angular_rate_)
127  + angular_rate_.cross(angular_rate_); // we don't need the inertia matrix here
128 }
129 
virtual void CalculateRotorVelocities(Eigen::VectorXd *rotor_velocities) const
Eigen::MatrixX4d angular_acc_to_rotor_velocities_
void ComputeDesiredAngularAcc(Eigen::Vector3d *angular_acceleration) const
virtual std::shared_ptr< ControllerBase > Clone()
ROTORS_CONTROL_REGISTER_CONTROLLER(AttitudeControllerSamy)


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