30 double thrustCoefficient,
double torqueCoefficient,
31 double minMotorSpeed,
double maxMotorSpeed,
32 double motorTimeConstant,
double motorRotationalInertia,
34 const Eigen::Matrix3d & vehicleInertia,
35 const Eigen::Matrix3d & aeroMomentCoefficient,
36 double dragCoefficient,
37 double momentProcessNoiseAutoCorrelation,
38 double forceProcessNoiseAutoCorrelation,
39 const Eigen::Vector3d & gravity
41 : numCopter_(numCopter)
42 , motorFrame_(numCopter)
43 , motorDirection_(numCopter)
44 , motorRotationalInertia_(numCopter)
45 , thrustCoefficient_(numCopter)
46 , torqueCoefficient_(numCopter)
47 , motorSpeed_(numCopter)
48 , motorTimeConstant_(numCopter)
49 , maxMotorSpeed_(numCopter)
50 , minMotorSpeed_(numCopter)
54 for (
int indx = 0; indx < numCopter; indx++){
83 : numCopter_(numCopter)
84 , motorFrame_(numCopter)
85 , motorDirection_(numCopter)
86 , motorRotationalInertia_(numCopter)
87 , thrustCoefficient_(numCopter)
88 , torqueCoefficient_(numCopter)
89 , motorSpeed_(numCopter)
90 , motorTimeConstant_(numCopter)
91 , maxMotorSpeed_(numCopter)
92 , minMotorSpeed_(numCopter)
96 for (
int indx = 0; indx < numCopter; indx++){
123 const Eigen::Matrix3d & vehicleInertia,
124 const Eigen::Matrix3d & aeroMomentCoefficient,
125 double dragCoefficient,
126 double momentProcessNoiseAutoCorrelation,
127 double forceProcessNoiseAutoCorrelation){
172 double minMotorSpeed,
double maxMotorSpeed,
double rotationalInertia,
int motorIndex){
192 double minMotorSpeed,
double maxMotorSpeed,
double rotationalInertia){
193 for (
int motorIndex = 0; motorIndex <
numCopter_; motorIndex++){
195 minMotorSpeed, maxMotorSpeed, rotationalInertia, motorIndex);
216 for (
int motorIndex = 0; motorIndex <
numCopter_; motorIndex++){
226 for (
int indx = 0; indx <
numCopter_; indx++){
238 const Eigen::Quaterniond & attitude){
262 const Eigen::Vector3d & velocity,
263 const Eigen::Vector3d & angularVelocity,
264 const Eigen::Quaterniond & attitude,
265 const std::vector<double> & motorSpeed){
270 for (
int indx = 0; indx <
numCopter_; indx++){
285 Eigen::Vector3d & velocity,
286 Eigen::Vector3d & angularVelocity,
287 Eigen::Quaterniond & attitude,
288 std::vector<double> & motorSpeed){
346 return specificForce;
367 Eigen::Vector3d thrust = Eigen::Vector3d::Zero();
368 for (
int indx = 0; indx <
numCopter_; indx++){
370 Eigen::Vector3d motorThrust(0.,0.,fabs(motorSpeed.at(indx))*motorSpeed.at(indx)*
thrustCoefficient_.at(indx));
371 thrust +=
motorFrame_.at(indx).linear()*motorThrust;
384 Eigen::Vector3d controlMoment = Eigen::Vector3d::Zero();
386 for (
int indx = 0; indx <
numCopter_; indx++){
388 Eigen::Vector3d motorThrust(0.,0.,fabs(motorSpeed.at(indx))*motorSpeed.at(indx)*
thrustCoefficient_.at(indx));
394 controlMoment +=
motorFrame_.at(indx).linear()*motorTorque;
397 return controlMoment;
428 Eigen::Vector3d zero_force;
429 zero_force.setZero();
444 std::vector<double> motorSpeedCommand = motorSpeedCommandIn;
447 for (
size_t i = 0; i < motorSpeedCommand.size(); i++)
453 std::vector<double> motorSpeedCommandBounded(
numCopter_);
463 Eigen::Vector3d stochMoment;
468 std::vector<double> motorSpeedDer(
numCopter_);
470 Eigen::Vector3d positionDer = velocity;
477 position_ = position + positionDer*dt_secs;
478 velocity_ = velocity + velocityDer*dt_secs;
480 attitude_.coeffs() = attitude.coeffs() + attitudeDer*dt_secs;
505 std::vector<double> motorSpeedCommand = motorSpeedCommandIn;
509 for (
size_t i = 0; i < motorSpeedCommand.size(); i++)
514 std::vector<double> motorSpeedCommandBounded(
numCopter_);
525 Eigen::Vector3d stochMoment;
531 std::vector<double> motorSpeedDer(
numCopter_);
533 Eigen::Vector3d positionDer = dt_secs*
velocity_;
541 position += (1./6.)*positionDer;
542 velocity += (1./6.)*velocityDer;
543 attitude.coeffs() += (1./6.)*attitudeDer;
544 attitude.normalize();
545 angularVelocity += (1./6.)*angularVelocityDer;
548 std::vector<double> motorSpeedIntermediate(
numCopter_);
549 Eigen::Quaterniond attitudeIntermediate;
553 attitudeIntermediate.coeffs() =
attitude_.coeffs() + attitudeDer*0.5;
554 attitudeIntermediate.normalize();
557 positionDer = dt_secs*(
velocity_ + 0.5*velocityDer);
565 position += (1./3.)*positionDer;
566 velocity += (1./3.)*velocityDer;
567 attitude.coeffs() += (1./3.)*attitudeDer;
568 attitude.normalize();
569 angularVelocity += (1./3.)*angularVelocityDer;
574 attitudeIntermediate.coeffs() =
attitude_.coeffs() + attitudeDer*0.5;
575 attitudeIntermediate.normalize();
578 positionDer = dt_secs*(
velocity_ + 0.5*velocityDer);
586 position += (1./3.)*positionDer;
587 velocity += (1./3.)*velocityDer;
588 attitude.coeffs() += (1./3.)*attitudeDer;
589 attitude.normalize();
590 angularVelocity += (1./3.)*angularVelocityDer;
595 attitudeIntermediate.coeffs() =
attitude_.coeffs() + attitudeDer;
596 attitudeIntermediate.normalize();
599 positionDer = dt_secs*(
velocity_ + velocityDer);
608 position_ = position + positionDer*(1./6.);
609 velocity_ = velocity + velocityDer*(1./6.);
610 attitude_.coeffs() = attitude.coeffs() + attitudeDer*(1./6.);
630 std::vector<double> & vec3,
double val){
631 std::transform(vec1.begin(), vec1.end(), vec2.begin(), vec3.begin(), [val](
const double & vec1val,
const double & vec2val)->double{return (vec1val + val*vec2val);});
643 const std::vector<double> & minvec,
const std::vector<double> & maxvec){
644 std::transform(vec1.begin(), vec1.end(), maxvec.begin(), vec2.begin(), [](
const double & vec1val,
const double & maxvalue)->double{return fmin(vec1val,maxvalue);});
645 std::transform(vec2.begin(), vec2.end(), minvec.begin(), vec2.begin(), [](
const double & vec2val,
const double & minvalue)->double{return fmax(vec2val,minvalue);});
656 std::transform(vec1.begin(), vec1.end(), vec2.begin(), [val](
const double & vec1val){return vec1val*val;});
667 const std::vector<double> & motorSpeed,
668 const std::vector<double> & motorSpeedCommand){
669 for (
int indx = 0; indx <
numCopter_; indx++){
670 motorSpeedDer.at(indx) = (motorSpeedCommand.at(indx) - motorSpeed.at(indx))/
motorTimeConstant_.at(indx);
684 const Eigen::Vector3d & velocity,
const std::vector<double> & motorSpeed){
696 Eigen::Quaterniond angularVelocityQuad;
697 angularVelocityQuad.w() = 0;
698 angularVelocityQuad.vec() = angularVelocity;
700 return (0.5*(attitude*angularVelocityQuad).coeffs());
713 const std::vector<double>& motorAcceleration,
const Eigen::Vector3d & angularVelocity,
const Eigen::Vector3d & stochMoment){
717 for (
int indx = 0; indx <
numCopter_; indx++){
718 Eigen::Vector3d motorAngularMomentum = Eigen::Vector3d::Zero();
722 angularMomentum +=
motorFrame_.at(indx).linear()*motorAngularMomentum;
726 - angularVelocity.cross(angularMomentum)));