multirotor_forces_and_moments.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017 Daniel Koch, James Jackson and Gary Ellingson, BYU MAGICC Lab.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice, this
9  * list of conditions and the following disclaimer.
10  *
11  * * Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * * Neither the name of the copyright holder nor the names of its
16  * contributors may be used to endorse or promote products derived from
17  * this software without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  */
31 
33 
34 namespace rosflight_sim
35 {
36 
38 {
39  nh_ = nh;
40 
41  // Pull Parameters off of rosparam server
42  num_rotors_ = 0;
43  ROS_ASSERT_MSG(nh_->getParam("ground_effect", ground_effect_), "missing parameters in %s namespace", nh_->getNamespace().c_str());
44  ROS_ASSERT(nh_->getParam("mass", mass_));
45  ROS_ASSERT(nh_->getParam("linear_mu", linear_mu_));
46  ROS_ASSERT(nh_->getParam("angular_mu", angular_mu_));
47  ROS_ASSERT(nh_->getParam("num_rotors", num_rotors_));
48 
49  std::vector<double> rotor_positions(3 * num_rotors_);
50  std::vector<double> rotor_vector_normal(3 * num_rotors_);
51  std::vector<int> rotor_rotation_directions(num_rotors_);
52 
53  // For now, just assume all rotors are the same
54  Rotor rotor;
55 
56  ROS_ASSERT(nh_->getParam("rotor_positions", rotor_positions));
57  ROS_ASSERT(nh_->getParam("rotor_vector_normal", rotor_vector_normal));
58  ROS_ASSERT(nh_->getParam("rotor_rotation_directions", rotor_rotation_directions));
59  ROS_ASSERT(nh_->getParam("rotor_max_thrust", rotor.max));
60  ROS_ASSERT(nh_->getParam("rotor_F", rotor.F_poly));
61  ROS_ASSERT(nh_->getParam("rotor_T", rotor.T_poly));
62  ROS_ASSERT(nh_->getParam("rotor_tau_up", rotor.tau_up));
63  ROS_ASSERT(nh_->getParam("rotor_tau_down", rotor.tau_down));
64 
65  /* Load Rotor Configuration */
66  motors_.resize(num_rotors_);
67 
70  for(int i = 0; i < num_rotors_; i++)
71  {
72  motors_[i].rotor = rotor;
73  motors_[i].position.resize(3);
74  motors_[i].normal.resize(3);
75  for (int j = 0; j < 3; j++)
76  {
77  motors_[i].position(j) = rotor_positions[3*i + j];
78  motors_[i].normal(j) = rotor_vector_normal[3*i + j];
79  }
80  motors_[i].normal.normalize();
81  motors_[i].direction = rotor_rotation_directions[i];
82 
83  Eigen::Vector3d moment_from_thrust = motors_[i].position.cross(motors_[i].normal);
84  Eigen::Vector3d moment_from_torque = motors_[i].direction * motors_[i].normal;
85 
86  // build allocation_matrices
87  force_allocation_matrix_(0,i) = moment_from_thrust(0); // l
88  force_allocation_matrix_(1,i) = moment_from_thrust(1); // m
89  force_allocation_matrix_(2,i) = moment_from_thrust(2); // n
90  force_allocation_matrix_(3,i) = motors_[i].normal(2); // F
91 
92  torque_allocation_matrix_(0,i) = moment_from_torque(0); // l
93  torque_allocation_matrix_(1,i) = moment_from_torque(1); // m
94  torque_allocation_matrix_(2,i) = moment_from_torque(2); // n
95  torque_allocation_matrix_(3,i) = 0.0; // F
96  }
97 
98  ROS_INFO_STREAM("allocation matrices:\nFORCE \n" << force_allocation_matrix_ << "\nTORQUE\n" << torque_allocation_matrix_ << "\n");
99 
100  // Initialize size of dynamic force and torque matrices
101  desired_forces_.resize(num_rotors_);
102  desired_torques_.resize(num_rotors_);
103  actual_forces_.resize(num_rotors_);
104  actual_torques_.resize(num_rotors_);
105 
106  for (int i = 0; i < num_rotors_; i++)
107  {
108  desired_forces_(i)=0.0;
109  desired_torques_(i)=0.0;
110  actual_forces_(i)=0.0;
111  actual_torques_(i)=0.0;
112  }
113 
114  wind_ = Eigen::Vector3d::Zero();
115  prev_time_ = -1;
116 }
117 
118 Eigen::Matrix<double, 6, 1> Multirotor::updateForcesAndTorques(Current_State x, const int act_cmds[])
119 {
120  if (prev_time_ < 0)
121  {
122  prev_time_ = x.t;
123  return Eigen::Matrix<double, 6, 1>::Zero();
124  }
125 
126  double dt = x.t - prev_time_;
127  double pd = x.pos[2];
128 
129  // Get airspeed vector for drag force calculation (rotate wind into body frame and add to inertial velocity)
130  Eigen::Vector3d Va = x.vel + x.rot.inverse()*wind_;
131 
132  // Calculate Forces
133  for (int i = 0; i<num_rotors_; i++)
134  {
135  // First, figure out the desired force output from passing the signal into the quadratic approximation
136  double signal = act_cmds[i];
137  desired_forces_(i,0) = motors_[i].rotor.F_poly[0]*signal*signal + motors_[i].rotor.F_poly[1]*signal + motors_[i].rotor.F_poly[2];
138  desired_torques_(i,0) = motors_[i].rotor.T_poly[0]*signal*signal + motors_[i].rotor.T_poly[1]*signal + motors_[i].rotor.T_poly[2];
139 
140  // Then, Calculate Actual force and torque for each rotor using first-order dynamics
141  double tau = (desired_forces_(i,0) > actual_forces_(i,0)) ? motors_[i].rotor.tau_up : motors_[i].rotor.tau_down;
142  double alpha = dt/(tau + dt);
143  actual_forces_(i,0) = sat((1-alpha)*actual_forces_(i) + alpha*desired_forces_(i), motors_[i].rotor.max, 0.0);
144  actual_torques_(i,0) = sat((1-alpha)*actual_torques_(i) + alpha*desired_torques_(i), motors_[i].rotor.max, 0.0);
145  }
146 
147  // Use the allocation matrix to calculate the body-fixed force and torques
148  Eigen::Vector4d output_forces = force_allocation_matrix_*actual_forces_;
149  Eigen::Vector4d output_torques = torque_allocation_matrix_*actual_torques_;
150  Eigen::Vector4d output_forces_and_torques = output_forces + output_torques;
151 
152  // Calculate Ground Effect
153  double z = -pd;
154  double ground_effect = max(ground_effect_[0]*z*z*z*z + ground_effect_[1]*z*z*z + ground_effect_[2]*z*z + ground_effect_[3]*z + ground_effect_[4], 0);
155 
156  Eigen::Matrix<double, 6,1> forces;
157  // Apply other forces (drag) <- follows "Quadrotors and Accelerometers - State Estimation With an Improved Dynamic Model"
158  // By Rob Leishman et al.
159  forces.block<3,1>(3,0) = -linear_mu_ * Va;
160  forces.block<3,1>(3,0) = -angular_mu_ * x.omega + output_forces_and_torques.block<3,1>(0,0);
161 
162  // Apply ground effect and thrust
163  forces(2) += output_forces_and_torques(3) - ground_effect;
164 
165  return forces;
166 }
167 
168 void Multirotor::set_wind(Eigen::Vector3d wind)
169 {
170  wind_ = wind;
171 }
172 
173 }
Eigen::Matrix< double, 6, 1 > updateForcesAndTorques(Current_State x, const int act_cmds[])
#define ROS_ASSERT_MSG(cond,...)
const std::string & getNamespace() const
TFSIMD_FORCE_INLINE const tfScalar & z() const
int i
double sat(double x, double max, double min)
#define ROS_INFO_STREAM(args)
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT(cond)


rosflight_sim
Author(s): James Jackson, Gary Ellingson, Daniel Koch
autogenerated on Wed Jul 3 2019 20:00:29