00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021 #include "rotors_control/attitude_controller_samy.h"
00022
00023 #include <iostream>
00024
00025 AttitudeControllerSamy::AttitudeControllerSamy()
00026 : gravity_(9.81),
00027 mass_(1.56779) {
00028 }
00029
00030 AttitudeControllerSamy::~AttitudeControllerSamy() {
00031 }
00032
00033 std::shared_ptr<ControllerBase> AttitudeControllerSamy::Clone() {
00034 std::shared_ptr<ControllerBase> controller(new AttitudeControllerSamy);
00035 return controller;
00036 }
00037
00038 void AttitudeControllerSamy::InitializeParams() {
00039 gain_attitude_(0) = 3;
00040 gain_attitude_(1) = 3;
00041 gain_attitude_(2) = 0.035;
00042
00043 gain_angular_rate_(0) = 0.52;
00044 gain_angular_rate_(1) = 0.52;
00045 gain_angular_rate_(2) = 0.025;
00046
00047 amount_rotors_ = 6;
00048 allocation_matrix_.resize(4,amount_rotors_);
00049 allocation_matrix_ << sin(M_PI/6), 1, sin(M_PI/6), -sin(M_PI/6), -1, -sin(M_PI/6),
00050 -cos(M_PI/6), 0, cos(M_PI/6), cos(M_PI/6), 0, -cos(M_PI/6),
00051 -1, 1, -1, 1, -1, 1,
00052 1, 1, 1, 1, 1, 1;
00053
00054 inertia_matrix_<< 0.0347563, 0, 0,
00055 0, 0.0458929, 0,
00056 0, 0, 0.0977;
00057
00058
00059 gain_attitude_ = gain_attitude_.transpose() * inertia_matrix_.inverse();
00060
00061
00062 gain_angular_rate_ = gain_angular_rate_.transpose() * inertia_matrix_.inverse();
00063
00064 const double rotor_force_constant = 0.00000854858;
00065 const double rotor_moment_constant = 0.016;
00066
00067 angular_acc_to_rotor_velocities_.resize(amount_rotors_, 4);
00068 const double arm_length = 0.215;
00069
00070 Eigen::Matrix4d K;
00071 K.setZero();
00072 K(0, 0) = arm_length * rotor_force_constant;
00073 K(1, 1) = arm_length * rotor_force_constant;
00074 K(2, 2) = rotor_force_constant * rotor_moment_constant;
00075 K(3, 3) = rotor_force_constant;
00076
00077 Eigen::Matrix4d I;
00078 I.setZero();
00079 I.block<3, 3>(0, 0) = inertia_matrix_;
00080 I(3, 3) = 1;
00081 angular_acc_to_rotor_velocities_ = allocation_matrix_.transpose()
00082 * (allocation_matrix_ * allocation_matrix_.transpose()).inverse() * K.inverse() * I;
00083 initialized_params_ = true;
00084 }
00085
00086 void AttitudeControllerSamy::CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const {
00087 assert(rotor_velocities);
00088 assert(initialized_params_);
00089
00090 rotor_velocities->resize(amount_rotors_);
00091
00092 Eigen::Vector3d angular_acceleration;
00093 ComputeDesiredAngularAcc(&angular_acceleration);
00094
00095 Eigen::Vector4d angular_acceleration_thrust;
00096 angular_acceleration_thrust.block<3, 1>(0, 0) = angular_acceleration;
00097 angular_acceleration_thrust(3) = control_attitude_thrust_reference_(3);
00098
00099 *rotor_velocities = angular_acc_to_rotor_velocities_ * angular_acceleration_thrust;
00100 *rotor_velocities = rotor_velocities->cwiseMax(Eigen::VectorXd::Ones(rotor_velocities->rows()));
00101 *rotor_velocities = rotor_velocities->cwiseSqrt();
00102 }
00103
00104
00105 void AttitudeControllerSamy::ComputeDesiredAngularAcc(Eigen::Vector3d* angular_acceleration) const {
00106 assert(angular_acceleration);
00107
00108 Eigen::Matrix3d R = attitude_.toRotationMatrix();
00109
00110
00111 Eigen::Matrix3d R_des;
00112 double yaw = atan2(R(1, 0), R(0, 0));
00113 R_des = Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ())
00114 * Eigen::AngleAxisd(control_attitude_thrust_reference_(0), Eigen::Vector3d::UnitX())
00115 * Eigen::AngleAxisd(control_attitude_thrust_reference_(1), Eigen::Vector3d::UnitY());
00116
00117 Eigen::Vector3d b3_des = R.transpose() * R_des.col(2);
00118 Eigen::Vector3d angle_error = b3_des.cross(Eigen::Vector3d::UnitZ());
00119
00120 Eigen::Vector3d angular_rate_des(Eigen::Vector3d::Zero());
00121 angular_rate_des[2] = control_attitude_thrust_reference_(2);
00122
00123 Eigen::Vector3d angular_rate_error = angular_rate_ - R_des.transpose() * R * angular_rate_des;
00124
00125 *angular_acceleration = -1 * angle_error.cwiseProduct(gain_attitude_)
00126 - angular_rate_error.cwiseProduct(gain_angular_rate_)
00127 + angular_rate_.cross(angular_rate_);
00128 }
00129
00130 ROTORS_CONTROL_REGISTER_CONTROLLER(AttitudeControllerSamy);