roll_pitch_yawrate_thrust_controller.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Fadri Furrer, ASL, ETH Zurich, Switzerland
00003  * Copyright 2015 Michael Burri, ASL, ETH Zurich, Switzerland
00004  * Copyright 2015 Mina Kamel, ASL, ETH Zurich, Switzerland
00005  * Copyright 2015 Janosch Nikolic, ASL, ETH Zurich, Switzerland
00006  * Copyright 2015 Markus Achtelik, ASL, ETH Zurich, Switzerland
00007  *
00008  * Licensed under the Apache License, Version 2.0 (the "License");
00009  * you may not use this file except in compliance with the License.
00010  * You may obtain a copy of the License at
00011  *
00012  *     http://www.apache.org/licenses/LICENSE-2.0
00013 
00014  * Unless required by applicable law or agreed to in writing, software
00015  * distributed under the License is distributed on an "AS IS" BASIS,
00016  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00017  * See the License for the specific language governing permissions and
00018  * limitations under the License.
00019  */
00020 
00021 #ifndef ROTORS_CONTROL_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H
00022 #define ROTORS_CONTROL_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H
00023 
00024 #include <mav_msgs/conversions.h>
00025 #include <mav_msgs/eigen_mav_msgs.h>
00026 
00027 #include "rotors_control/common.h"
00028 #include "rotors_control/parameters.h"
00029 
00030 namespace rotors_control {
00031 
00032 // Default values for the roll pitch yawrate thrust controller and the Asctec Firefly.
00033 static const Eigen::Vector3d kDefaultAttitudeGain = Eigen::Vector3d(3, 3, 0.035);
00034 static const Eigen::Vector3d kDefaultAngularRateGain = Eigen::Vector3d(0.52, 0.52, 0.025);
00035 
00036 class RollPitchYawrateThrustControllerParameters {
00037  public:
00038   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00039   RollPitchYawrateThrustControllerParameters()
00040       : attitude_gain_(kDefaultAttitudeGain),
00041         angular_rate_gain_(kDefaultAngularRateGain) {
00042     calculateAllocationMatrix(rotor_configuration_, &allocation_matrix_);
00043   }
00044 
00045   Eigen::Matrix4Xd allocation_matrix_;
00046   Eigen::Vector3d attitude_gain_;
00047   Eigen::Vector3d angular_rate_gain_;
00048   RotorConfiguration rotor_configuration_;
00049 };
00050 
00051 class RollPitchYawrateThrustController {
00052  public:
00053   RollPitchYawrateThrustController();
00054   ~RollPitchYawrateThrustController();
00055   void InitializeParameters();
00056   void CalculateRotorVelocities(Eigen::VectorXd* rotor_velocities) const;
00057 
00058   void SetOdometry(const EigenOdometry& odometry);
00059   void SetRollPitchYawrateThrust(
00060       const mav_msgs::EigenRollPitchYawrateThrust& roll_pitch_yawrate_thrust);
00061 
00062   RollPitchYawrateThrustControllerParameters controller_parameters_;
00063   VehicleParameters vehicle_parameters_;
00064 
00065   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00066  private:
00067   bool initialized_params_;
00068   bool controller_active_;
00069 
00070   Eigen::Vector3d normalized_attitude_gain_;
00071   Eigen::Vector3d normalized_angular_rate_gain_;
00072   Eigen::MatrixX4d angular_acc_to_rotor_velocities_;
00073 
00074   mav_msgs::EigenRollPitchYawrateThrust roll_pitch_yawrate_thrust_;
00075   EigenOdometry odometry_;
00076 
00077   void ComputeDesiredAngularAcc(Eigen::Vector3d* angular_acceleration) const;
00078 };
00079 }
00080 
00081 #endif // ROTORS_CONTROL_ROLL_PITCH_YAWRATE_THRUST_CONTROLLER_H


rotors_control
Author(s): Fadri Furrer, Michael Burri, Mina Kamel, Janosch Nikolic, Markus Achtelik
autogenerated on Thu Apr 18 2019 02:43:38