@@ -18,7 +18,7 @@ namespace MbD {
|
||||
void parseASMT(std::vector<std::string>& lines) override;
|
||||
void storeOnLevel(std::ofstream& os, int level) override;
|
||||
|
||||
int nframe = 1000000, icurrent = 0, istart = 0, iend = 1000000, framesPerSecond = 30;
|
||||
int nframe = 1000000, icurrent = 1, istart = 1, iend = 1000000, framesPerSecond = 30;
|
||||
bool isForward = true;
|
||||
|
||||
|
||||
|
||||
@@ -940,7 +940,7 @@ void MbD::ASMTAssembly::createMbD(std::shared_ptr<System> mbdSys, std::shared_pt
|
||||
void MbD::ASMTAssembly::outputFile(std::string filename)
|
||||
{
|
||||
std::ofstream os(filename);
|
||||
os << std::setprecision(std::numeric_limits<double>::digits10 + 1);
|
||||
os << std::setprecision(static_cast<std::streamsize>(std::numeric_limits<double>::digits10) + 1);
|
||||
// try {
|
||||
os << "OndselSolver" << std::endl;
|
||||
storeOnLevel(os, 0);
|
||||
@@ -1144,7 +1144,7 @@ std::shared_ptr<ASMTPart> MbD::ASMTAssembly::partPartialNamed(std::string partia
|
||||
auto fullName = prt->fullName("");
|
||||
return fullName.find(partialName) != std::string::npos;
|
||||
});
|
||||
auto part = *it;
|
||||
auto& part = *it;
|
||||
return part;
|
||||
}
|
||||
|
||||
@@ -1212,6 +1212,7 @@ void MbD::ASMTAssembly::storeOnLevelGeneralConstraintSets(std::ofstream& os, int
|
||||
|
||||
void MbD::ASMTAssembly::storeOnTimeSeries(std::ofstream& os)
|
||||
{
|
||||
if (times->empty()) return;
|
||||
os << "TimeSeries" << std::endl;
|
||||
os << "Number\tInput\t";
|
||||
for (int i = 1; i < times->size(); i++)
|
||||
|
||||
@@ -121,7 +121,7 @@ namespace MbD {
|
||||
void storeOnLevelGeneralConstraintSets(std::ofstream& os, int level);
|
||||
void storeOnTimeSeries(std::ofstream& os) override;
|
||||
|
||||
std::string notes;
|
||||
std::string notes = "(Text string: '' runs: (Core.RunArray runs: #() values: #()))";
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTPart>>> parts = std::make_shared<std::vector<std::shared_ptr<ASMTPart>>>();
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTKinematicIJ>>> kinematicIJs = std::make_shared<std::vector<std::shared_ptr<ASMTKinematicIJ>>>();
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTConstraintSet>>> constraintSets = std::make_shared<std::vector<std::shared_ptr<ASMTConstraintSet>>>();
|
||||
@@ -129,11 +129,11 @@ namespace MbD {
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTMotion>>> motions = std::make_shared<std::vector<std::shared_ptr<ASMTMotion>>>();
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTForceTorque>>> forcesTorques = std::make_shared<std::vector<std::shared_ptr<ASMTForceTorque>>>();
|
||||
std::shared_ptr<ASMTConstantGravity> constantGravity = std::make_shared<ASMTConstantGravity>();
|
||||
std::shared_ptr<ASMTSimulationParameters> simulationParameters;
|
||||
std::shared_ptr<ASMTAnimationParameters> animationParameters;
|
||||
std::shared_ptr<std::vector<double>> times;
|
||||
std::shared_ptr<ASMTSimulationParameters> simulationParameters = std::make_shared<ASMTSimulationParameters>();
|
||||
std::shared_ptr<ASMTAnimationParameters> animationParameters = std::make_shared<ASMTAnimationParameters>();
|
||||
std::shared_ptr<std::vector<double>> times = std::make_shared<std::vector<double>>();
|
||||
std::shared_ptr<ASMTTime> asmtTime = std::make_shared<ASMTTime>();
|
||||
std::shared_ptr<Units> mbdUnits;
|
||||
std::shared_ptr<Units> mbdUnits = std::make_shared<Units>();
|
||||
MBDynSystem* mbdynItem = nullptr;
|
||||
};
|
||||
}
|
||||
|
||||
@@ -92,21 +92,21 @@ void MbD::ASMTGeneralMotion::createMbD(std::shared_ptr<System> mbdSys, std::shar
|
||||
userFunc = std::make_shared<BasicUserFunction>(rIJI->at(0), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoX = parser->stack->top();
|
||||
geoX = Symbolic::times(geoX, std::make_shared<Constant>(1.0 / mbdUnits->length));
|
||||
geoX = Symbolic::times(geoX, sptrConstant(1.0 / mbdUnits->length));
|
||||
geoX->createMbD(mbdSys, mbdUnits);
|
||||
auto xBlk = geoX->simplified(geoX);
|
||||
|
||||
userFunc = std::make_shared<BasicUserFunction>(rIJI->at(1), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoY = parser->stack->top();
|
||||
geoY = Symbolic::times(geoY, std::make_shared<Constant>(1.0 / mbdUnits->length));
|
||||
geoY = Symbolic::times(geoY, sptrConstant(1.0 / mbdUnits->length));
|
||||
geoY->createMbD(mbdSys, mbdUnits);
|
||||
auto yBlk = geoY->simplified(geoY);
|
||||
|
||||
userFunc = std::make_shared<BasicUserFunction>(rIJI->at(2), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoZ = parser->stack->top();
|
||||
geoZ = Symbolic::times(geoZ, std::make_shared<Constant>(1.0 / mbdUnits->length));
|
||||
geoZ = Symbolic::times(geoZ, sptrConstant(1.0 / mbdUnits->length));
|
||||
geoZ->createMbD(mbdSys, mbdUnits);
|
||||
auto zBlk = geoZ->simplified(geoZ);
|
||||
|
||||
@@ -117,21 +117,21 @@ void MbD::ASMTGeneralMotion::createMbD(std::shared_ptr<System> mbdSys, std::shar
|
||||
userFunc = std::make_shared<BasicUserFunction>(angIJJ->at(0), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoPhi = parser->stack->top();
|
||||
geoPhi = Symbolic::times(geoPhi, std::make_shared<Constant>(1.0 / mbdUnits->angle));
|
||||
geoPhi = Symbolic::times(geoPhi, sptrConstant(1.0 / mbdUnits->angle));
|
||||
geoPhi->createMbD(mbdSys, mbdUnits);
|
||||
auto phiBlk = geoPhi->simplified(geoPhi);
|
||||
|
||||
userFunc = std::make_shared<BasicUserFunction>(angIJJ->at(1), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoThe = parser->stack->top();
|
||||
geoThe = Symbolic::times(geoThe, std::make_shared<Constant>(1.0 / mbdUnits->angle));
|
||||
geoThe = Symbolic::times(geoThe, sptrConstant(1.0 / mbdUnits->angle));
|
||||
geoThe->createMbD(mbdSys, mbdUnits);
|
||||
auto theBlk = geoThe->simplified(geoThe);
|
||||
|
||||
userFunc = std::make_shared<BasicUserFunction>(angIJJ->at(2), 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoPsi = parser->stack->top();
|
||||
geoPsi = Symbolic::times(geoPsi, std::make_shared<Constant>(1.0 / mbdUnits->angle));
|
||||
geoPsi = Symbolic::times(geoPsi, sptrConstant(1.0 / mbdUnits->angle));
|
||||
geoPsi->createMbD(mbdSys, mbdUnits);
|
||||
auto psiBlk = geoPsi->simplified(geoPsi);
|
||||
|
||||
|
||||
@@ -25,11 +25,14 @@ void MbD::ASMTPointInPlaneJoint::parseASMT(std::vector<std::string>& lines)
|
||||
|
||||
void MbD::ASMTPointInPlaneJoint::readOffset(std::vector<std::string>& lines)
|
||||
{
|
||||
assert(lines[0].find("offset") != std::string::npos);
|
||||
lines.erase(lines.begin());
|
||||
offset = readDouble(lines[0]);
|
||||
lines.erase(lines.begin());
|
||||
|
||||
if (lines[0].find("offset") == std::string::npos) {
|
||||
offset = 0.0;
|
||||
}
|
||||
else {
|
||||
lines.erase(lines.begin());
|
||||
offset = readDouble(lines[0]);
|
||||
lines.erase(lines.begin());
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::ASMTPointInPlaneJoint::createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<Units> mbdUnits)
|
||||
|
||||
@@ -12,6 +12,11 @@
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
MbD::ASMTPrincipalMassMarker::ASMTPrincipalMassMarker()
|
||||
{
|
||||
name = "MassMarker";
|
||||
}
|
||||
|
||||
void MbD::ASMTPrincipalMassMarker::parseASMT(std::vector<std::string>& lines)
|
||||
{
|
||||
size_t pos = lines[0].find_first_not_of("\t");
|
||||
|
||||
@@ -5,29 +5,30 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "ASMTSpatialItem.h"
|
||||
|
||||
namespace MbD {
|
||||
class EXPORT ASMTPrincipalMassMarker : public ASMTSpatialItem
|
||||
{
|
||||
//
|
||||
public:
|
||||
void parseASMT(std::vector<std::string>& lines) override;
|
||||
void setMass(double mass);
|
||||
void setDensity(double density);
|
||||
void setMomentOfInertias(DiagMatDsptr momentOfInertias);
|
||||
class EXPORT ASMTPrincipalMassMarker : public ASMTSpatialItem
|
||||
{
|
||||
//
|
||||
public:
|
||||
ASMTPrincipalMassMarker();
|
||||
void parseASMT(std::vector<std::string>& lines) override;
|
||||
void setMass(double mass);
|
||||
void setDensity(double density);
|
||||
void setMomentOfInertias(DiagMatDsptr momentOfInertias);
|
||||
|
||||
// Overloads to simplify syntax.
|
||||
void setMomentOfInertias(double a, double b, double c);
|
||||
void storeOnLevel(std::ofstream& os, int level) override;
|
||||
// Overloads to simplify syntax.
|
||||
void setMomentOfInertias(double a, double b, double c);
|
||||
void storeOnLevel(std::ofstream& os, int level) override;
|
||||
|
||||
double mass = 0.0;
|
||||
double density = 0.0;
|
||||
DiagMatDsptr momentOfInertias = std::make_shared<DiagonalMatrix>(ListD{ 0.,0.,0. });
|
||||
double mass = 1.0;
|
||||
double density = 10.0;
|
||||
DiagMatDsptr momentOfInertias = std::make_shared<DiagonalMatrix>(ListD{ 1.0, 2.0, 3.0 });
|
||||
|
||||
};
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
@@ -68,9 +68,13 @@ void MbD::ASMTRotationalMotion::createMbD(std::shared_ptr<System> mbdSys, std::s
|
||||
auto userFunc = std::make_shared<BasicUserFunction>(rotationZ, 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto geoPhi = parser->stack->top();
|
||||
geoPhi = Symbolic::times(geoPhi, std::make_shared<Constant>(1.0 / mbdUnits->angle));
|
||||
std::cout << *geoPhi << std::endl;
|
||||
geoPhi = Symbolic::times(geoPhi, sptrConstant(1.0 / mbdUnits->angle));
|
||||
geoPhi->createMbD(mbdSys, mbdUnits);
|
||||
std::static_pointer_cast<ZRotation>(mbdObject)->phiBlk = geoPhi->simplified(geoPhi);
|
||||
std::cout << *geoPhi << std::endl;
|
||||
auto simple = geoPhi->simplified(geoPhi);
|
||||
std::cout << *simple << std::endl;
|
||||
std::static_pointer_cast<ZRotation>(mbdObject)->phiBlk = simple;
|
||||
}
|
||||
|
||||
std::shared_ptr<Joint> MbD::ASMTRotationalMotion::mbdClassNew()
|
||||
|
||||
@@ -550,13 +550,25 @@ void MbD::ASMTSpatialContainer::setOmega3D(double a, double b, double c)
|
||||
void MbD::ASMTSpatialContainer::storeOnLevelVelocity(std::ofstream& os, int level)
|
||||
{
|
||||
storeOnLevelString(os, level, "Velocity3D");
|
||||
storeOnLevelArray(os, level + 1, *velocity3D);
|
||||
if (vxs == nullptr || vxs->empty()) {
|
||||
storeOnLevelArray(os, level + 1, *velocity3D);
|
||||
}
|
||||
else {
|
||||
auto array = getVelocity3D(0);
|
||||
storeOnLevelArray(os, level + 1, *array);
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::ASMTSpatialContainer::storeOnLevelOmega(std::ofstream& os, int level)
|
||||
{
|
||||
storeOnLevelString(os, level, "Omega3D");
|
||||
storeOnLevelArray(os, level + 1, *omega3D);
|
||||
if (omexs == nullptr || omexs->empty()) {
|
||||
storeOnLevelArray(os, level + 1, *omega3D);
|
||||
}
|
||||
else {
|
||||
auto array = getOmega3D(0);
|
||||
storeOnLevelArray(os, level + 1, *array);
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::ASMTSpatialContainer::storeOnLevelRefPoints(std::ofstream& os, int level)
|
||||
@@ -697,3 +709,21 @@ void MbD::ASMTSpatialContainer::storeOnTimeSeries(std::ofstream& os)
|
||||
}
|
||||
os << std::endl;
|
||||
}
|
||||
|
||||
FColDsptr MbD::ASMTSpatialContainer::getVelocity3D(size_t i)
|
||||
{
|
||||
auto vec3 = std::make_shared<FullColumn<double>>(3);
|
||||
vec3->atiput(0, vxs->at(i));
|
||||
vec3->atiput(1, vys->at(i));
|
||||
vec3->atiput(2, vzs->at(i));
|
||||
return vec3;
|
||||
}
|
||||
|
||||
FColDsptr MbD::ASMTSpatialContainer::getOmega3D(size_t i)
|
||||
{
|
||||
auto vec3 = std::make_shared<FullColumn<double>>(3);
|
||||
vec3->atiput(0, omexs->at(i));
|
||||
vec3->atiput(1, omeys->at(i));
|
||||
vec3->atiput(2, omezs->at(i));
|
||||
return vec3;
|
||||
}
|
||||
|
||||
@@ -86,16 +86,16 @@ namespace MbD {
|
||||
void storeOnLevelRefCurves(std::ofstream& os, int level);
|
||||
void storeOnLevelRefSurfaces(std::ofstream& os, int level);
|
||||
void storeOnTimeSeries(std::ofstream& os) override;
|
||||
FColDsptr getVelocity3D(size_t i);
|
||||
FColDsptr getOmega3D(size_t i);
|
||||
|
||||
FColDsptr velocity3D = std::make_shared<FullColumn<double>>(3);
|
||||
FColDsptr omega3D = std::make_shared<FullColumn<double>>(3);
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTRefPoint>>> refPoints;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTRefCurve>>> refCurves;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<ASMTRefSurface>>> refSurfaces;
|
||||
FRowDsptr xs, ys, zs, bryxs, bryys, bryzs;
|
||||
FRowDsptr vxs, vys, vzs, omexs, omeys, omezs;
|
||||
FRowDsptr axs, ays, azs, alpxs, alpys, alpzs;
|
||||
FRowDsptr inxs, inys, inzs, inbryxs, inbryys, inbryzs;
|
||||
FRowDsptr invxs, invys, invzs, inomexs, inomeys, inomezs;
|
||||
FRowDsptr inaxs, inays, inazs, inalpxs, inalpys, inalpzs;
|
||||
std::shared_ptr<ASMTPrincipalMassMarker> principalMassMarker = std::make_shared<ASMTPrincipalMassMarker>();
|
||||
|
||||
@@ -10,6 +10,7 @@
|
||||
#include "Units.h"
|
||||
#include "Part.h"
|
||||
#include "ASMTSpatialContainer.h"
|
||||
#include "EulerAngles.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
@@ -102,14 +103,50 @@ void MbD::ASMTSpatialItem::storeOnLevel(std::ofstream& os, int level)
|
||||
void MbD::ASMTSpatialItem::storeOnLevelPosition(std::ofstream& os, int level)
|
||||
{
|
||||
storeOnLevelString(os, level, "Position3D");
|
||||
storeOnLevelArray(os, level + 1, *position3D);
|
||||
if (xs == nullptr || xs->empty()) {
|
||||
storeOnLevelArray(os, level + 1, *position3D);
|
||||
}
|
||||
else {
|
||||
auto array = getPosition3D(0);
|
||||
storeOnLevelArray(os, level + 1, *array);
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::ASMTSpatialItem::storeOnLevelRotationMatrix(std::ofstream& os, int level)
|
||||
{
|
||||
storeOnLevelString(os, level, "RotationMatrix");
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
storeOnLevelArray(os, level + 1, *rotationMatrix->at(i));
|
||||
if (xs == nullptr || xs->empty()) {
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
storeOnLevelArray(os, level + 1, *rotationMatrix->at(i));
|
||||
}
|
||||
}
|
||||
else {
|
||||
auto rotMat = getRotationMatrix(0);
|
||||
for (int i = 0; i < 3; i++)
|
||||
{
|
||||
storeOnLevelArray(os, level + 1, *rotMat->at(i));
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
FColDsptr MbD::ASMTSpatialItem::getPosition3D(size_t i)
|
||||
{
|
||||
auto vec3 = std::make_shared<FullColumn<double>>(3);
|
||||
vec3->atiput(0, xs->at(i));
|
||||
vec3->atiput(1, ys->at(i));
|
||||
vec3->atiput(2, zs->at(i));
|
||||
return vec3;
|
||||
}
|
||||
|
||||
FMatDsptr MbD::ASMTSpatialItem::getRotationMatrix(size_t i)
|
||||
{
|
||||
auto bryantAngles = std::make_shared<EulerAngles<double>>();
|
||||
bryantAngles->setRotOrder(1, 2, 3);
|
||||
bryantAngles->at(0) = bryxs->at(i);
|
||||
bryantAngles->at(1) = bryys->at(i);
|
||||
bryantAngles->at(2) = bryzs->at(i);
|
||||
bryantAngles->calc();
|
||||
return bryantAngles->aA;
|
||||
}
|
||||
|
||||
@@ -31,6 +31,8 @@ namespace MbD {
|
||||
void storeOnLevel(std::ofstream& os, int level) override;
|
||||
void storeOnLevelPosition(std::ofstream& os, int level);
|
||||
void storeOnLevelRotationMatrix(std::ofstream& os, int level);
|
||||
FColDsptr getPosition3D(size_t i);
|
||||
FMatDsptr getRotationMatrix(size_t i);
|
||||
|
||||
FColDsptr position3D = std::make_shared<FullColumn<double>>(3);
|
||||
FMatDsptr rotationMatrix = std::make_shared<FullMatrixDouble>(ListListD{
|
||||
@@ -38,6 +40,9 @@ namespace MbD {
|
||||
{ 0, 1, 0 },
|
||||
{ 0, 0, 1 }
|
||||
});
|
||||
FRowDsptr xs, ys, zs, bryxs, bryys, bryzs;
|
||||
FRowDsptr inxs, inys, inzs, inbryxs, inbryys, inbryzs;
|
||||
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
@@ -25,7 +25,27 @@ void MbD::ASMTTime::createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<Un
|
||||
{
|
||||
auto mbdTime = mbdSys->time;
|
||||
if (xx == mbdTime) return;
|
||||
auto timeScale = std::make_shared<Constant>(mbdUnits->time);
|
||||
auto timeScale = sptrConstant(mbdUnits->time);
|
||||
auto geoTime = std::make_shared<Product>(timeScale, mbdTime);
|
||||
this->xexpression(mbdTime, geoTime->simplified(geoTime));
|
||||
}
|
||||
|
||||
Symsptr MbD::ASMTTime::expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
return sptr;
|
||||
}
|
||||
|
||||
Symsptr MbD::ASMTTime::simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
return sptr;
|
||||
}
|
||||
|
||||
bool MbD::ASMTTime::isVariable()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
void MbD::ASMTTime::setValue(double val)
|
||||
{
|
||||
xx->setValue(val);
|
||||
}
|
||||
|
||||
@@ -19,6 +19,10 @@ namespace MbD {
|
||||
public:
|
||||
void deleteMbD();
|
||||
void createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<Units> mbdUnits);
|
||||
Symsptr expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
Symsptr simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
bool isVariable() override;
|
||||
void setValue(double val) override;
|
||||
|
||||
};
|
||||
}
|
||||
|
||||
@@ -42,7 +42,7 @@ void MbD::ASMTTranslationalMotion::createMbD(std::shared_ptr<System> mbdSys, std
|
||||
auto userFunc = std::make_shared<BasicUserFunction>(translationZ, 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto zIJ = parser->stack->top();
|
||||
zIJ = Symbolic::times(zIJ, std::make_shared<Constant>(1.0 / mbdUnits->length));
|
||||
zIJ = Symbolic::times(zIJ, sptrConstant(1.0 / mbdUnits->length));
|
||||
zIJ->createMbD(mbdSys, mbdUnits);
|
||||
std::static_pointer_cast<ZTranslation>(mbdObject)->zBlk = zIJ->simplified(zIJ);
|
||||
}
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::Abs::getValue()
|
||||
return std::abs(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::Abs::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<Abs>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::Abs::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "abs(" << xx << ")";
|
||||
s << "abs(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
Abs() = default;
|
||||
Abs(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::ArcSine::getValue()
|
||||
return std::asin(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::ArcSine::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<ArcSine>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::ArcSine::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "arcsin(" << xx << ")";
|
||||
s << "arcsin(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
ArcSine() = default;
|
||||
ArcSine(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::ArcTan::getValue()
|
||||
return std::atan(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::ArcTan::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<ArcTan>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::ArcTan::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "arctan(" << xx << ")";
|
||||
s << "arctan(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
ArcTan() = default;
|
||||
ArcTan(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -16,5 +16,5 @@ MbD::ArcTan2::ArcTan2(Symsptr arg, Symsptr arg1) : FunctionXY(arg, arg1)
|
||||
|
||||
double MbD::ArcTan2::getValue()
|
||||
{
|
||||
return std::atan2(y->getValue(), x->getValue());;
|
||||
return std::atan2(y->getValue(), x->getValue());
|
||||
}
|
||||
|
||||
@@ -121,7 +121,7 @@ namespace MbD {
|
||||
{
|
||||
for (int ii = 0; ii < this->size(); ii++)
|
||||
{
|
||||
this->at(ii) = array->at(i + ii);
|
||||
this->at(ii) = array->at((size_t)i + ii);
|
||||
}
|
||||
}
|
||||
//template<>
|
||||
@@ -182,4 +182,4 @@ namespace MbD {
|
||||
{
|
||||
this->at(i) *= factor;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -45,7 +45,7 @@ void AtPointConstraintIqcJc::useEquationNumbers()
|
||||
void AtPointConstraintIqcJc::fillPosICError(FColDsptr col)
|
||||
{
|
||||
Constraint::fillPosICError(col);
|
||||
col->at(iqXIminusOnePlusAxis) -= lam;
|
||||
col->atiminusNumber(iqXIminusOnePlusAxis, lam);
|
||||
col->atiplusFullVectortimes(iqEI, pGpEI, lam);
|
||||
}
|
||||
|
||||
|
||||
@@ -46,7 +46,7 @@ void AtPointConstraintIqcJqc::useEquationNumbers()
|
||||
void AtPointConstraintIqcJqc::fillPosICError(FColDsptr col)
|
||||
{
|
||||
AtPointConstraintIqcJc::fillPosICError(col);
|
||||
col->at(iqXJminusOnePlusAxis) += lam;
|
||||
col->atiplusNumber(iqXJminusOnePlusAxis, lam);
|
||||
col->atiplusFullVectortimes(iqEJ, pGpEJ, lam);
|
||||
}
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include "BasicIntegrator.h"
|
||||
#include "CREATE.h"
|
||||
#include "StableBackwardDifference.h"
|
||||
|
||||
@@ -14,15 +14,15 @@ using namespace MbD;
|
||||
void BasicQuasiIntegrator::firstStep()
|
||||
{
|
||||
istep = 0;
|
||||
this->preFirstStep();
|
||||
preFirstStep();
|
||||
iTry = 1;
|
||||
orderNew = 1;
|
||||
this->selectFirstStepSize();
|
||||
this->incrementTime();
|
||||
this->runInitialConditionTypeSolution();
|
||||
//this->reportTrialStepStats();
|
||||
this->postFirstStep();
|
||||
//this->reportStepStats();
|
||||
selectFirstStepSize();
|
||||
incrementTime();
|
||||
runInitialConditionTypeSolution();
|
||||
//reportTrialStepStats();
|
||||
postFirstStep();
|
||||
//reportStepStats();
|
||||
}
|
||||
|
||||
bool BasicQuasiIntegrator::isRedoingFirstStep()
|
||||
@@ -32,15 +32,15 @@ bool BasicQuasiIntegrator::isRedoingFirstStep()
|
||||
|
||||
void BasicQuasiIntegrator::nextStep()
|
||||
{
|
||||
this->preStep();
|
||||
preStep();
|
||||
iTry = 1;
|
||||
this->selectOrder();
|
||||
this->selectStepSize();
|
||||
this->incrementTime();
|
||||
this->runInitialConditionTypeSolution();
|
||||
//this->reportTrialStepStats();
|
||||
this->postStep();
|
||||
//this->reportStepStats();
|
||||
selectOrder();
|
||||
selectStepSize();
|
||||
incrementTime();
|
||||
runInitialConditionTypeSolution();
|
||||
//reportTrialStepStats();
|
||||
postStep();
|
||||
//reportStepStats();
|
||||
}
|
||||
|
||||
void BasicQuasiIntegrator::runInitialConditionTypeSolution()
|
||||
|
||||
@@ -78,7 +78,7 @@ namespace MbD {
|
||||
else {
|
||||
inst = std::make_shared<AtPointConstraintIqcJqc>(frmi, frmj, axis);
|
||||
}
|
||||
} // "class MbD::Tran
|
||||
}
|
||||
else if(str.find("TranslationConstraintIJ") != std::string::npos) {
|
||||
if (std::dynamic_pointer_cast<EndFrameqct>(frmi)) {
|
||||
inst = std::make_shared<TranslationConstraintIqctJqc>(frmi, frmj, axis);
|
||||
|
||||
@@ -1,2 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<ClassDiagram />
|
||||
@@ -1,11 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<ClassDiagram MajorVersion="1" MinorVersion="1">
|
||||
<Class Name="MbD::Solver" Collapsed="true">
|
||||
<Position X="0.5" Y="0.5" Width="1.5" />
|
||||
<TypeIdentifier>
|
||||
<HashCode>AKAAAgAAAAAAgAAAEAEAAIABAAAAAAAACIAAIAAAAAI=</HashCode>
|
||||
<FileName>Solver.h</FileName>
|
||||
</TypeIdentifier>
|
||||
</Class>
|
||||
<Font Name="Segoe UI" Size="9" />
|
||||
</ClassDiagram>
|
||||
@@ -52,40 +52,40 @@ void ConstVelConstraintIJ::postInput()
|
||||
{
|
||||
aA01IeJe->postInput();
|
||||
aA10IeJe->postInput();
|
||||
Constraint::postInput();
|
||||
ConstraintIJ::postInput();
|
||||
}
|
||||
|
||||
void ConstVelConstraintIJ::postPosICIteration()
|
||||
{
|
||||
aA01IeJe->postPosICIteration();
|
||||
aA10IeJe->postPosICIteration();
|
||||
Item::postPosICIteration();
|
||||
ConstraintIJ::postPosICIteration();
|
||||
}
|
||||
|
||||
void ConstVelConstraintIJ::preAccIC()
|
||||
{
|
||||
aA01IeJe->preAccIC();
|
||||
aA10IeJe->preAccIC();
|
||||
Constraint::preAccIC();
|
||||
ConstraintIJ::preAccIC();
|
||||
}
|
||||
|
||||
void ConstVelConstraintIJ::prePosIC()
|
||||
{
|
||||
aA01IeJe->prePosIC();
|
||||
aA10IeJe->prePosIC();
|
||||
Constraint::prePosIC();
|
||||
ConstraintIJ::prePosIC();
|
||||
}
|
||||
|
||||
void ConstVelConstraintIJ::preVelIC()
|
||||
{
|
||||
aA01IeJe->preVelIC();
|
||||
aA10IeJe->preVelIC();
|
||||
Item::preVelIC();
|
||||
ConstraintIJ::preVelIC();
|
||||
}
|
||||
|
||||
void ConstVelConstraintIJ::simUpdateAll()
|
||||
{
|
||||
aA01IeJe->simUpdateAll();
|
||||
aA10IeJe->simUpdateAll();
|
||||
Item::simUpdateAll();
|
||||
ConstraintIJ::simUpdateAll();
|
||||
}
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include <memory>
|
||||
|
||||
#include "ConstVelConstraintIqcJc.h"
|
||||
|
||||
@@ -9,6 +9,7 @@
|
||||
#include "Constant.h"
|
||||
#include "System.h"
|
||||
#include "Units.h"
|
||||
#include "Polynomial.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
@@ -22,7 +23,23 @@ Constant::Constant(double val) : Variable(val)
|
||||
|
||||
Symsptr MbD::Constant::differentiateWRT(Symsptr var)
|
||||
{
|
||||
return std::make_shared<Constant>(0.0);
|
||||
return sptrConstant(0.0);
|
||||
}
|
||||
|
||||
Symsptr MbD::Constant::integrateWRT(Symsptr var)
|
||||
{
|
||||
if (value == 0.0) return clonesptr();
|
||||
auto slope = sptrConstant(value);
|
||||
auto intercept = sptrConstant(0.0);
|
||||
auto coeffs = std::make_shared<std::vector<Symsptr>>();
|
||||
coeffs->push_back(intercept);
|
||||
coeffs->push_back(slope);
|
||||
return std::make_shared<Polynomial>(var, coeffs);
|
||||
}
|
||||
|
||||
Symsptr MbD::Constant::expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
return sptr;
|
||||
}
|
||||
|
||||
bool Constant::isConstant()
|
||||
@@ -30,11 +47,6 @@ bool Constant::isConstant()
|
||||
return true;
|
||||
}
|
||||
|
||||
Symsptr MbD::Constant::expandUntil(std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
return clonesptr();
|
||||
}
|
||||
|
||||
Symsptr MbD::Constant::clonesptr()
|
||||
{
|
||||
return std::make_shared<Constant>(*this);
|
||||
@@ -60,6 +72,11 @@ double MbD::Constant::getValue()
|
||||
return value;
|
||||
}
|
||||
|
||||
double MbD::Constant::getValue(double arg)
|
||||
{
|
||||
return value;
|
||||
}
|
||||
|
||||
std::ostream& Constant::printOn(std::ostream& s) const
|
||||
{
|
||||
return s << this->value;
|
||||
|
||||
@@ -17,13 +17,15 @@ namespace MbD {
|
||||
Constant();
|
||||
Constant(double val);
|
||||
Symsptr differentiateWRT(Symsptr var) override;
|
||||
Symsptr integrateWRT(Symsptr var) override;
|
||||
Symsptr expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
bool isConstant() override;
|
||||
Symsptr expandUntil(std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
Symsptr clonesptr() override;
|
||||
bool isZero() override;
|
||||
bool isOne() override;
|
||||
void createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<Units> mbdUnits) override;
|
||||
double getValue() override;
|
||||
double getValue(double arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
};
|
||||
|
||||
@@ -15,6 +15,6 @@ using namespace MbD;
|
||||
void MbD::ConstantGravity::fillAccICIterError(FColDsptr col)
|
||||
{
|
||||
for (auto& part : *(root()->parts)) {
|
||||
col->atiplusFullColumn(part->iqX(), gXYZ->times(part->m));
|
||||
col->atiplusFullColumntimes(part->iqX(), gXYZ, part->m);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -104,7 +104,7 @@ void Constraint::setqsudotlam(FColDsptr col)
|
||||
|
||||
void Constraint::fillPosICError(FColDsptr col)
|
||||
{
|
||||
col->at(iG) += aG;
|
||||
col->atiplusNumber(iG, aG);
|
||||
}
|
||||
|
||||
void Constraint::removeRedundantConstraints(std::shared_ptr<std::vector<int>> redundantEqnNos)
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <memory>
|
||||
|
||||
@@ -26,8 +26,13 @@ Symsptr MbD::Cosine::differentiateWRTx()
|
||||
return std::make_shared<Negative>(std::make_shared<Sine>(xx));
|
||||
}
|
||||
|
||||
Symsptr MbD::Cosine::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<Cosine>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::Cosine::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "cos(" << xx << ")";
|
||||
s << "cos(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -19,6 +19,7 @@ namespace MbD {
|
||||
Cosine(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr differentiateWRTx() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
297
OndselSolver/CrankSlider2.mbd
Normal file
297
OndselSolver/CrankSlider2.mbd
Normal file
@@ -0,0 +1,297 @@
|
||||
-----------------------------------------------------------------------------
|
||||
# [Data Block]
|
||||
|
||||
begin: data;
|
||||
problem: initial value;
|
||||
end: data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Problem Block]
|
||||
|
||||
begin: initial value;
|
||||
initial time: 0.0;
|
||||
final time: 8.0;
|
||||
time step: 0.01;
|
||||
max iterations: 100;
|
||||
tolerance: 1e-06;
|
||||
derivatives tolerance: 0.0001;
|
||||
derivatives max iterations: 100;
|
||||
derivatives coefficient: auto;
|
||||
end: initial value;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Control Data Block]
|
||||
|
||||
begin: control data;
|
||||
max iterations: 1000;
|
||||
default orientation: euler321;
|
||||
omega rotates: no;
|
||||
print: none;
|
||||
initial stiffness: 1.0, 1.0;
|
||||
structural nodes: 4;
|
||||
rigid bodies: 3;
|
||||
joints: 6;
|
||||
end: control data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Design Variables]
|
||||
|
||||
#Generic bodies
|
||||
|
||||
#body: 2
|
||||
set: integer body_2 = 2; #body label
|
||||
set: real mass_2 = 3.805252376198168; #mass [kg]
|
||||
set: real volume_2 = 0.0004816775159744516; #volume [m^3]
|
||||
|
||||
#body: 3
|
||||
set: integer body_3 = 3; #body label
|
||||
set: real mass_3 = 15.238784954845523; #mass [kg]
|
||||
set: real volume_3 = 0.0019289601208665218; #volume [m^3]
|
||||
|
||||
#body: 4
|
||||
set: integer body_4 = 4; #body label
|
||||
set: real mass_4 = 2.865603331977783; #mass [kg]
|
||||
set: real volume_4 = 0.0003627345989845295; #volume [m^3]
|
||||
|
||||
#Nodes
|
||||
|
||||
#node: 1
|
||||
set: integer structural_node_1 = 1; #node label
|
||||
|
||||
#node: 2
|
||||
set: integer structural_node_2 = 2; #node label
|
||||
|
||||
#node: 3
|
||||
set: integer structural_node_3 = 3; #node label
|
||||
|
||||
#node: 4
|
||||
set: integer structural_node_4 = 4; #node label
|
||||
|
||||
#Joints
|
||||
|
||||
#joint: 1
|
||||
set: integer joint_1 = 1; #joint label
|
||||
|
||||
#joint: 2
|
||||
set: integer joint_2 = 2; #joint label
|
||||
|
||||
#joint: 3
|
||||
set: integer joint_3 = 3; #joint label
|
||||
|
||||
#joint: 4
|
||||
set: integer joint_4 = 4; #joint label
|
||||
|
||||
#joint: 5
|
||||
set: integer joint_5 = 5; #joint label
|
||||
|
||||
#joint: 6
|
||||
set: integer joint_6 = 6; #joint label
|
||||
|
||||
#Nodes: initial conditions
|
||||
|
||||
#node: 1
|
||||
set: real Px_1 = -0.06210573361337854; #X component of the absolute position [m]
|
||||
set: real Py_1 = 0.048526435375479564; #Y component of the absolute position [m]
|
||||
set: real Pz_1 = -4.033966837940965e-17; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_1 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_1 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_1 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_1 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_1 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_1 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 2
|
||||
set: real Px_2 = 0.011666006676941875; #X component of the absolute position [m]
|
||||
set: real Py_2 = 0.15999999999999778; #Y component of the absolute position [m]
|
||||
set: real Pz_2 = -1.2084363289349542e-19; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_2 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_2 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_2 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_2 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_2 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_2 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 3
|
||||
set: real Px_3 = 0.2111281366952498; #X component of the absolute position [m]
|
||||
set: real Py_3 = 0.16; #Y component of the absolute position [m]
|
||||
set: real Pz_3 = -2.0217697810416158e-18; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_3 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_3 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_3 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_3 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_3 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_3 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 4
|
||||
set: real Px_4 = -0.1812239275015207; #X component of the absolute position [m]
|
||||
set: real Py_4 = 0.16000000169909329; #Y component of the absolute position [m]
|
||||
set: real Pz_4 = -4.340477856936436e-12; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_4 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_4 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_4 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_4 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_4 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_4 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Intermediate Variables]
|
||||
|
||||
#Moments of inertia and relative center of mass
|
||||
|
||||
#body 2:
|
||||
set: real Ixx_2 = 0.031674420620509; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_2 = 0.029604112147595; #moment of inertia [kg*m^2]
|
||||
set: real Izz_2 = 0.002867529429125; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_2 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_2 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_2 = 2.0843632893495426e-20; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 3:
|
||||
set: real Ixx_3 = 0.09813066341583701; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_3 = 0.095433846761275; #moment of inertia [kg*m^2]
|
||||
set: real Izz_3 = 0.077043262824289; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_3 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_3 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_3 = 2.1769781041615487e-20; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 4:
|
||||
set: real Ixx_4 = 0.010133521085753; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_4 = 0.006853402672398001; #moment of inertia [kg*m^2]
|
||||
set: real Izz_4 = 0.00669113151275; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_4 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_4 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_4 = -4.306356366563123e-20; #Z component of the relative center of mass [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Nodes Block]
|
||||
|
||||
begin: nodes;
|
||||
|
||||
structural: structural_node_1,
|
||||
static,
|
||||
Px_1, Py_1, Pz_1, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_1, Vy_1, Vz_1, #<absolute_velocity> [m/s]
|
||||
Wx_1, Wy_1, Wz_1; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_2,
|
||||
dynamic,
|
||||
Px_2, Py_2, Pz_2, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_2, Vy_2, Vz_2, #<absolute_velocity> [m/s]
|
||||
Wx_2, Wy_2, Wz_2; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_3,
|
||||
dynamic,
|
||||
Px_3, Py_3, Pz_3, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_3, Vy_3, Vz_3, #<absolute_velocity> [m/s]
|
||||
Wx_3, Wy_3, Wz_3; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_4,
|
||||
dynamic,
|
||||
Px_4, Py_4, Pz_4, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_4, Vy_4, Vz_4, #<absolute_velocity> [m/s]
|
||||
Wx_4, Wy_4, Wz_4; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
end: nodes;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Elements Block]
|
||||
|
||||
begin: elements;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Bodies]
|
||||
|
||||
body: body_2,
|
||||
structural_node_2, #<node_label>
|
||||
mass_2, #<mass> [kg]
|
||||
Rx_2, Ry_2, Rz_2, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_2, Iyy_2, Izz_2, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 1.0, 0.0, 0.0, 2, 0.0, 0.9999999999999999, 9.62964972193618e-35;
|
||||
|
||||
body: body_3,
|
||||
structural_node_3, #<node_label>
|
||||
mass_3, #<mass> [kg]
|
||||
Rx_3, Ry_3, Rz_3, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_3, Iyy_3, Izz_3, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 1.0, 0.0, 0.0;
|
||||
|
||||
body: body_4,
|
||||
structural_node_4, #<node_label>
|
||||
mass_4, #<mass> [kg]
|
||||
Rx_4, Ry_4, Rz_4, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_4, Iyy_4, Izz_4, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Joints]
|
||||
|
||||
joint: joint_1,
|
||||
clamp,
|
||||
structural_node_1, #<node_label>
|
||||
-0.06210573361337854, 0.048526435375479564, -4.033966837940965e-17, #<absolute_pin_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_2,
|
||||
axial rotation,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.2521057336133785, 0.11147356462452043, 0.13500000000000004, #<relative_offset_1> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, -1.0, 2.220446049250313e-16, 0.0, #<relative_orientation_matrix_1>
|
||||
structural_node_3, #<node_2_label>
|
||||
-0.021128136695249794, 0.0, 0.135, #<relative_offset_2> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, -1.0, 2.220446049250313e-16, 0.0, #<relative_orientation_matrix_2>
|
||||
string, "model::drive(1, Time)"; #<angular_velocity> [rad/s]
|
||||
|
||||
joint: joint_3,
|
||||
revolute hinge,
|
||||
structural_node_2, #<node_1_label>
|
||||
0.08833399332305812, 2.2168933355715126e-15, 0.065, #<relative_position_1> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, -1.0, 2.220446049250313e-16, 0.0, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_3, #<node_2_label>
|
||||
-0.11112813669524979, 0.0, 0.065, #<relative_position_2> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, -1.0, 2.220446049250313e-16, 0.0; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_4,
|
||||
prismatic,
|
||||
structural_node_1, #<node_1_label>
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #relative_orientation_matrix_1>
|
||||
structural_node_4, #<node_2_label>
|
||||
orientation, 3, 0, 0, 1, 2, 0, 1, 0; #relative_orientation_matrix_2>
|
||||
|
||||
joint: joint_5,
|
||||
in line,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.0, 0.11147355803101042, 2.4118673970779456e-17, #<relative_line_position> [m]
|
||||
3, -1.0, 1.1102230246251565e-16, -2.220446049250313e-16, 2, -1.1102230246251565e-16, 0.0, 1.0, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, 0.0, -8.292603282173139e-09, 4.340448411165876e-12; #<relative_offset> [m]
|
||||
|
||||
joint: joint_6,
|
||||
in line,
|
||||
structural_node_2, #<node_1_label>
|
||||
-0.1616660066769419, 2.2168933355715126e-15, 0.0, #<relative_line_position> [m]
|
||||
3, 0.0, -0.0, -1.0, 2, -1.0, -2.220446049250313e-16, 0.0, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, 0.031223927501520705, -1.69909327496498e-09, 7.275957614183426e-15; #<relative_offset> [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Drive callers]
|
||||
|
||||
drive caller: 1, name,"drive:1", ramp, 10.0, 0.0, 1.0, 0.0;
|
||||
|
||||
end: elements;
|
||||
|
||||
3204
OndselSolver/CrankSlider2.mov
Normal file
3204
OndselSolver/CrankSlider2.mov
Normal file
File diff suppressed because it is too large
Load Diff
@@ -25,7 +25,7 @@ namespace MbD {
|
||||
DiagonalMatrix(int count, const double& value) : Array<double>(count, value) {}
|
||||
DiagonalMatrix(std::initializer_list<double> list) : Array<double>{ list } {}
|
||||
void atiputDiagonalMatrix(int i, std::shared_ptr<DiagonalMatrix> diagMat);
|
||||
DiagMatDsptr times(double factor);
|
||||
DiagMatDsptr times(double factor);
|
||||
FColsptr<double> timesFullColumn(FColsptr<double> fullCol);
|
||||
FMatDsptr timesFullMatrix(FMatDsptr fullMat);
|
||||
int nrow() {
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include <cmath>
|
||||
|
||||
#include "DifferenceOperator.h"
|
||||
@@ -20,7 +20,7 @@ FRowDsptr DifferenceOperator::OneOverFactorials = []() {
|
||||
auto oneOverFactorials = std::make_shared<FullRow<double>>(10);
|
||||
for (int i = 0; i < oneOverFactorials->size(); i++)
|
||||
{
|
||||
oneOverFactorials->at(i) = 1.0 / std::tgamma(i+1);
|
||||
oneOverFactorials->at(i) = 1.0 / std::tgamma(i + 1);
|
||||
}
|
||||
return oneOverFactorials;
|
||||
}();
|
||||
@@ -42,6 +42,12 @@ void DifferenceOperator::calcOperatorMatrix()
|
||||
|
||||
void DifferenceOperator::initialize()
|
||||
{
|
||||
//Do nothing
|
||||
}
|
||||
|
||||
void MbD::DifferenceOperator::initializeLocally()
|
||||
{
|
||||
assert(false);
|
||||
}
|
||||
|
||||
void DifferenceOperator::setiStep(int i)
|
||||
@@ -75,9 +81,8 @@ void DifferenceOperator::formTaylorRowwithTimeNodederivative(int i, int ii, int
|
||||
for (int j = k + 1; j < order + 1; j++)
|
||||
{
|
||||
hipower = hipower * hi;
|
||||
assert(false);
|
||||
//aij = hipower * (OneOverFactorials at : j - k - 1);
|
||||
//rowi at : j put : aij
|
||||
auto aij = hipower * OneOverFactorials->at((size_t)j - k);
|
||||
rowi->atiput(j, aij);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -19,6 +19,7 @@ namespace MbD {
|
||||
public:
|
||||
void calcOperatorMatrix();
|
||||
virtual void initialize();
|
||||
virtual void initializeLocally();
|
||||
virtual void setiStep(int i);
|
||||
virtual void setorder(int o);
|
||||
virtual void formTaylorMatrix() = 0;
|
||||
@@ -29,7 +30,7 @@ namespace MbD {
|
||||
int iStep = 0, order = 0;
|
||||
FMatDsptr taylorMatrix, operatorMatrix;
|
||||
double time = 0.0;
|
||||
std::shared_ptr<std::vector<double>> timeNodes;
|
||||
std::shared_ptr<std::vector<double>> timeNodes; //"Row of past times in order of increasing past."
|
||||
static FRowDsptr OneOverFactorials;
|
||||
};
|
||||
}
|
||||
|
||||
@@ -34,6 +34,6 @@ Symsptr MbD::DifferentiatedGeneralSpline::clonesptr()
|
||||
|
||||
std::ostream& MbD::DifferentiatedGeneralSpline::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "deriv(" << generalSpline << ", " << derivativeOrder << ")";
|
||||
s << "deriv(" << *generalSpline << ", " << derivativeOrder << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -59,7 +59,7 @@ void DirectionCosineConstraintIJ::prePosIC()
|
||||
void DirectionCosineConstraintIJ::postPosICIteration()
|
||||
{
|
||||
aAijIeJe->postPosICIteration();
|
||||
Item::postPosICIteration();
|
||||
ConstraintIJ::postPosICIteration();
|
||||
}
|
||||
|
||||
ConstraintType DirectionCosineConstraintIJ::type()
|
||||
@@ -70,7 +70,7 @@ ConstraintType DirectionCosineConstraintIJ::type()
|
||||
void DirectionCosineConstraintIJ::preVelIC()
|
||||
{
|
||||
aAijIeJe->preVelIC();
|
||||
Item::preVelIC();
|
||||
ConstraintIJ::preVelIC();
|
||||
}
|
||||
|
||||
void MbD::DirectionCosineConstraintIJ::simUpdateAll()
|
||||
|
||||
@@ -321,4 +321,3 @@ namespace MbD {
|
||||
ppAOeptpt = aAOm->timesFullMatrix(ppAmeptpt);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::Exponential::getValue()
|
||||
return std::log(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::Exponential::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<Exponential>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::Exponential::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "exp(" << xx << ")";
|
||||
s << "exp(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
Exponential() = default;
|
||||
Exponential(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
***************************************************************************/
|
||||
|
||||
#include "ExpressionX.h"
|
||||
#include "Constant.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
@@ -23,8 +24,14 @@ void MbD::ExpressionX::xexpression(Symsptr arg, Symsptr func)
|
||||
expression = func;
|
||||
}
|
||||
|
||||
Symsptr MbD::ExpressionX::differentiateWRTx()
|
||||
{
|
||||
return expression->differentiateWRT(xx);
|
||||
}
|
||||
|
||||
Symsptr MbD::ExpressionX::differentiateWRT(Symsptr var)
|
||||
{
|
||||
if (this == var.get()) return sptrConstant(1.0);
|
||||
return expression->differentiateWRT(var);
|
||||
}
|
||||
|
||||
|
||||
@@ -17,6 +17,7 @@ namespace MbD {
|
||||
public:
|
||||
|
||||
void xexpression(Symsptr arg, Symsptr func);
|
||||
Symsptr differentiateWRTx() override;
|
||||
Symsptr differentiateWRT(Symsptr var) override;
|
||||
double getValue() override;
|
||||
|
||||
|
||||
@@ -169,5 +169,36 @@ namespace MbD {
|
||||
// instantiate on purpose to make visible in library api:
|
||||
template class FullColumn<double>;
|
||||
template class FullColumn<int>;
|
||||
template<typename T>
|
||||
double FullColumn<T>::dot(std::shared_ptr<FullVector<T>> vec)
|
||||
{
|
||||
int n = (int)this->size();
|
||||
double answer = 0.0;
|
||||
for (int i = 0; i < n; i++) {
|
||||
answer += this->at(i) * vec->at(i);
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
template<typename T>
|
||||
std::shared_ptr<FullVector<T>> FullColumn<T>::dot(std::shared_ptr<std::vector<std::shared_ptr<FullColumn<T>>>> vecvec)
|
||||
{
|
||||
int ncol = (int)this->size();
|
||||
auto nelem = vecvec->at(0)->size();
|
||||
auto answer = std::make_shared<FullVector<T>>(nelem);
|
||||
for (int k = 0; k < nelem; k++) {
|
||||
auto sum = 0.0;
|
||||
for (int i = 0; i < ncol; i++)
|
||||
{
|
||||
sum += this->at(i) * vecvec->at(i)->at(k);
|
||||
}
|
||||
answer->at(k) = sum;
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
template<typename T>
|
||||
std::shared_ptr<FullColumn<T>> FullColumn<T>::clonesptr()
|
||||
{
|
||||
return std::make_shared<FullColumn<T>>(*this);
|
||||
}
|
||||
|
||||
}
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <string>
|
||||
@@ -31,6 +31,7 @@ namespace MbD {
|
||||
FullColumn(typename std::vector<T>::iterator begin, typename std::vector<T>::iterator end) : FullVector<T>(begin, end) {}
|
||||
FullColumn(std::initializer_list<T> list) : FullVector<T>{ list } {}
|
||||
FColsptr<T> plusFullColumn(FColsptr<T> fullCol);
|
||||
FColsptr<T> plusFullColumntimes(FColsptr<T> fullCol, double factor);
|
||||
FColsptr<T> minusFullColumn(FColsptr<T> fullCol);
|
||||
FColsptr<T> times(T a);
|
||||
FColsptr<T> negated();
|
||||
@@ -42,10 +43,13 @@ namespace MbD {
|
||||
FColsptr<T> copy();
|
||||
FRowsptr<T> transpose();
|
||||
void atiplusFullColumntimes(int i, FColsptr<T> fullCol, T factor);
|
||||
T transposeTimesFullColumn(const FColsptr<T> fullCol);
|
||||
T transposeTimesFullColumn(const FColsptr<T> fullCol);
|
||||
void equalSelfPlusFullColumntimes(FColsptr<T> fullCol, T factor);
|
||||
FColsptr<T> cross(FColsptr<T> fullCol);
|
||||
FColsptr<T> simplified();
|
||||
std::shared_ptr<FullColumn<T>> clonesptr();
|
||||
double dot(std::shared_ptr<FullVector<T>> vec);
|
||||
std::shared_ptr<FullVector<T>> dot(std::shared_ptr<std::vector<std::shared_ptr<FullColumn<T>>>> vecvec);
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
};
|
||||
|
||||
@@ -22,6 +22,18 @@ namespace MbD {
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
//template<typename T>
|
||||
//inline FMatDsptr FullRow<T>::transposeTimesFullRow(FRowDsptr fullRow)
|
||||
//{
|
||||
// //"a*b = a(i)b(j)"
|
||||
// auto nrow = (int)this->size();
|
||||
// auto answer = std::make_shared<FullMatrixDouble>(nrow);
|
||||
// for (int i = 0; i < nrow; i++)
|
||||
// {
|
||||
// answer->atiput(i, fullRow->times(this->at(i)));
|
||||
// }
|
||||
// return answer;
|
||||
//}
|
||||
|
||||
template<>
|
||||
FRowsptr<double> FullRow<double>::timesTransposeFullMatrix(std::shared_ptr<FullMatrixDouble> fullMat)
|
||||
|
||||
@@ -35,9 +35,16 @@ namespace MbD {
|
||||
FColsptr<T> transpose();
|
||||
FRowsptr<T> copy();
|
||||
void atiplusFullRow(int j, FRowsptr<T> fullRow);
|
||||
FMatDsptr transposeTimesFullRow(FRowDsptr fullRow);
|
||||
std::shared_ptr<FullRow<T>> clonesptr();
|
||||
//double dot(std::shared_ptr<FullColumn<T>> vec);
|
||||
//double dot(std::shared_ptr<FullRow<T>> vec);
|
||||
double dot(std::shared_ptr<FullVector<T>> vec);
|
||||
std::shared_ptr<FullVector<T>> dot(std::shared_ptr<std::vector<std::shared_ptr<FullColumn<T>>>> vecvec);
|
||||
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
std::shared_ptr<FullMatrixDouble> transposeTimesFullRow(FRowsptr<double> fullRow);
|
||||
FRowsptr<double> timesTransposeFullMatrix(std::shared_ptr<FullMatrixDouble> fullMat);
|
||||
// FRowsptr<std::shared_ptr<FullMatrixDouble>> timesTransposeFullMatrixForFMFMDsptr(std::shared_ptr<FullMatrixFullMatrixDouble> fullMat);
|
||||
FRowsptr<double> timesFullMatrix(std::shared_ptr<FullMatrixDouble> fullMat);
|
||||
@@ -134,6 +141,37 @@ namespace MbD {
|
||||
}
|
||||
}
|
||||
template<typename T>
|
||||
inline std::shared_ptr<FullRow<T>> FullRow<T>::clonesptr()
|
||||
{
|
||||
return std::make_shared<FullRow<T>>(*this);
|
||||
}
|
||||
template<typename T>
|
||||
inline double FullRow<T>::dot(std::shared_ptr<FullVector<T>> vec)
|
||||
{
|
||||
int n = (int)this->size();
|
||||
double answer = 0.0;
|
||||
for (int i = 0; i < n; i++) {
|
||||
answer += this->at(i) * vec->at(i);
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
template<typename T>
|
||||
inline std::shared_ptr<FullVector<T>> FullRow<T>::dot(std::shared_ptr<std::vector<std::shared_ptr<FullColumn<T>>>> vecvec)
|
||||
{
|
||||
auto ncol = (int)this->size();
|
||||
auto nelem = vecvec->at(0)->size();
|
||||
auto answer = std::make_shared<FullVector<T>>(nelem);
|
||||
for (int k = 0; k < nelem; k++) {
|
||||
auto sum = 0.0;
|
||||
for (int i = 0; i < ncol; i++)
|
||||
{
|
||||
sum += this->at(i) * vecvec->at(i)->at(k);
|
||||
}
|
||||
answer->at(k) = sum;
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
template<typename T>
|
||||
inline std::ostream& FullRow<T>::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "FullRow{";
|
||||
|
||||
@@ -37,7 +37,12 @@ namespace MbD {
|
||||
void normalizeSelf();
|
||||
double length();
|
||||
virtual void conditionSelf();
|
||||
void conditionSelfWithTol(double tol);
|
||||
virtual void conditionSelfWithTol(double tol);
|
||||
std::shared_ptr<FullVector<T>> clonesptr();
|
||||
bool isIncreasing();
|
||||
bool isIncreasingIfExceptionsAreLessThan(double tol);
|
||||
bool isDecreasingIfExceptionsAreLessThan(double tol);
|
||||
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
@@ -183,6 +188,46 @@ namespace MbD {
|
||||
return; // Visual Studio demands the unused return
|
||||
}
|
||||
template<typename T>
|
||||
inline std::shared_ptr<FullVector<T>> FullVector<T>::clonesptr()
|
||||
{
|
||||
//Return shallow copy of *this wrapped in shared_ptr
|
||||
assert(false);
|
||||
return std::make_shared<FullVector<T>>(*this);
|
||||
}
|
||||
template<typename T>
|
||||
inline bool FullVector<T>::isIncreasing()
|
||||
{
|
||||
return isIncreasingIfExceptionsAreLessThan(0.0);
|
||||
}
|
||||
template<typename T>
|
||||
inline bool FullVector<T>::isIncreasingIfExceptionsAreLessThan(double tol)
|
||||
{
|
||||
//"Test if elements are increasing."
|
||||
//"Ok if spoilers are less than tol."
|
||||
auto next = this->at(0);
|
||||
for (int i = 1; i < this->size(); i++)
|
||||
{
|
||||
auto previous = next;
|
||||
next = this->at(i);
|
||||
if (previous > next && (previous - tol > next)) return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
template<typename T>
|
||||
inline bool FullVector<T>::isDecreasingIfExceptionsAreLessThan(double tol)
|
||||
{
|
||||
//"Test if elements are increasing."
|
||||
//"Ok if spoilers are less than tol."
|
||||
auto next = this->at(0);
|
||||
for (int i = 1; i < this->size(); i++)
|
||||
{
|
||||
auto previous = next;
|
||||
next = this->at(i);
|
||||
if (previous < next && (previous + tol < next)) return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
template<typename T>
|
||||
inline std::ostream& FullVector<T>::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "FullVec{";
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include "FunctionX.h"
|
||||
#include "Constant.h"
|
||||
#include "Sum.h"
|
||||
@@ -24,9 +24,43 @@ void MbD::FunctionX::arguments(Symsptr args)
|
||||
xx = sum->terms->front();
|
||||
}
|
||||
|
||||
Symsptr MbD::FunctionX::copyWith(Symsptr arg)
|
||||
{
|
||||
assert(false);
|
||||
return Symsptr();
|
||||
}
|
||||
|
||||
Symsptr MbD::FunctionX::expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
auto itr = std::find_if(set->begin(), set->end(), [sptr](Symsptr sym) {return sptr.get() == sym.get(); });
|
||||
if (itr != set->end()) return sptr;
|
||||
auto newx = xx->expandUntil(xx, set);
|
||||
auto copy = copyWith(newx);
|
||||
if (newx->isConstant()) {
|
||||
return sptrConstant(copy->getValue());
|
||||
}
|
||||
else {
|
||||
return copy;
|
||||
}
|
||||
}
|
||||
|
||||
Symsptr MbD::FunctionX::simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
auto itr = std::find_if(set->begin(), set->end(), [sptr](Symsptr sym) {return sptr.get() == sym.get(); });
|
||||
if (itr != set->end()) return sptr;
|
||||
auto newx = xx->simplifyUntil(xx, set);
|
||||
auto copy = copyWith(newx);
|
||||
if (newx->isConstant()) {
|
||||
return sptrConstant(copy->getValue());
|
||||
}
|
||||
else {
|
||||
return copy;
|
||||
}
|
||||
}
|
||||
|
||||
Symsptr MbD::FunctionX::differentiateWRT(Symsptr var)
|
||||
{
|
||||
if (this == var.get()) return std::make_shared<Constant>(1.0);
|
||||
if (this == var.get()) return sptrConstant(1.0);
|
||||
auto dfdx = differentiateWRTx();
|
||||
auto dxdvar = xx->differentiateWRT(var);
|
||||
return Symbolic::times(dfdx, dxdvar);
|
||||
@@ -42,3 +76,24 @@ void MbD::FunctionX::createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<U
|
||||
{
|
||||
xx->createMbD(mbdSys, mbdUnits);
|
||||
}
|
||||
|
||||
double MbD::FunctionX::getValue()
|
||||
{
|
||||
assert(false);
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
double MbD::FunctionX::getValue(double arg)
|
||||
{
|
||||
double answer;
|
||||
if (xx->isVariable()) {
|
||||
auto oldVal = xx->getValue();
|
||||
xx->setValue(arg);
|
||||
answer = getValue();
|
||||
xx->setValue(oldVal);
|
||||
}
|
||||
else {
|
||||
assert(false);
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
|
||||
@@ -21,9 +21,14 @@ namespace MbD {
|
||||
FunctionX() = default;
|
||||
FunctionX(Symsptr arg);
|
||||
void arguments(Symsptr args) override;
|
||||
virtual Symsptr copyWith(Symsptr arg);
|
||||
Symsptr expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
Symsptr simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
Symsptr differentiateWRT(Symsptr var) override;
|
||||
virtual Symsptr differentiateWRTx();
|
||||
void createMbD(std::shared_ptr<System> mbdSys, std::shared_ptr<Units> mbdUnits) override;
|
||||
double getValue() override;
|
||||
double getValue(double arg) override;
|
||||
|
||||
Symsptr xx;
|
||||
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#pragma once
|
||||
|
||||
#include "ConstraintIJ.h"
|
||||
#include "OrbitAnglezIecJec.h"
|
||||
#include "OrbitAngleZIecJec.h"
|
||||
|
||||
namespace MbD {
|
||||
class GearConstraintIJ : public ConstraintIJ
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "GearConstraintIqcJc.h"
|
||||
#include "EndFrameqc.h"
|
||||
#include "CREATE.h"
|
||||
#include "OrbitAnglezIeqcJec.h"
|
||||
#include "OrbitAngleZIeqcJec.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
#include "GearConstraintIqcJqc.h"
|
||||
#include "EndFrameqc.h"
|
||||
#include "OrbitAnglezIeqcJeqc.h"
|
||||
#include "OrbitAngleZIeqcJeqc.h"
|
||||
#include "CREATE.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
@@ -249,15 +249,13 @@ std::ostream& MbD::GeneralSpline::printOn(std::ostream& s) const
|
||||
{
|
||||
s << ", " << xs->at(i);
|
||||
}
|
||||
s << "}" << std::endl;;
|
||||
s << "}, " << std::endl;
|
||||
s << "ys{";
|
||||
s << ys->at(0);
|
||||
for (int i = 1; i < ys->size(); i++)
|
||||
{
|
||||
s << ", " << ys->at(i);
|
||||
}
|
||||
s << "}";
|
||||
s << ")";
|
||||
s << std::endl;
|
||||
s << "})" << std::endl;
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -21,7 +21,7 @@ namespace MbD {
|
||||
|
||||
void createInPlaneConstraint();
|
||||
|
||||
double offset;
|
||||
double offset = 0.0;
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
@@ -18,9 +18,9 @@ IndependentVariable::IndependentVariable()
|
||||
Symsptr MbD::IndependentVariable::differentiateWRT(Symsptr var)
|
||||
{
|
||||
if (this == var.get()) {
|
||||
return std::make_shared<Constant>(1.0);
|
||||
return sptrConstant(1.0);
|
||||
}
|
||||
else {
|
||||
return std::make_shared<Constant>(0.0);
|
||||
return sptrConstant(0.0);
|
||||
}
|
||||
}
|
||||
|
||||
45
OndselSolver/Integral.cpp
Normal file
45
OndselSolver/Integral.cpp
Normal file
@@ -0,0 +1,45 @@
|
||||
#include "Integral.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
MbD::Integral::Integral(Symsptr var, Symsptr integrand)
|
||||
{
|
||||
assert(false);
|
||||
}
|
||||
|
||||
void MbD::Integral::arguments(Symsptr args)
|
||||
{
|
||||
auto arguments = args->getTerms();
|
||||
xx = arguments->at(0);
|
||||
integrand = arguments->at(1);
|
||||
expression = integrand->integrateWRT(xx);
|
||||
}
|
||||
|
||||
Symsptr MbD::Integral::expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
auto expand = expression->expandUntil(expression, set);
|
||||
auto answer = std::make_shared<Integral>();
|
||||
answer->xx = xx;
|
||||
answer->expression = expand;
|
||||
answer->integrand = integrand;
|
||||
answer->integrationConstant = integrationConstant;
|
||||
return answer;
|
||||
}
|
||||
|
||||
Symsptr MbD::Integral::simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set)
|
||||
{
|
||||
auto simple = expression->simplifyUntil(expression, set);
|
||||
auto answer = std::make_shared<Integral>();
|
||||
answer->xx = xx;
|
||||
answer->expression = simple;
|
||||
answer->integrand = integrand;
|
||||
answer->integrationConstant = integrationConstant;
|
||||
return answer;
|
||||
}
|
||||
|
||||
std::ostream& MbD::Integral::printOn(std::ostream& s) const
|
||||
{
|
||||
s << *expression << " + ";
|
||||
s << *integrationConstant;
|
||||
return s;
|
||||
}
|
||||
29
OndselSolver/Integral.h
Normal file
29
OndselSolver/Integral.h
Normal file
@@ -0,0 +1,29 @@
|
||||
/***************************************************************************
|
||||
* Copyright (c) 2023 Ondsel, Inc. *
|
||||
* *
|
||||
* This file is part of OndselSolver. *
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "ExpressionX.h"
|
||||
#include "Constant.h"
|
||||
|
||||
namespace MbD {
|
||||
class Integral : public ExpressionX
|
||||
{
|
||||
public:
|
||||
Integral() = default;
|
||||
Integral(Symsptr var, Symsptr integrand);
|
||||
void arguments(Symsptr args) override;
|
||||
Symsptr expandUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
Symsptr simplifyUntil(Symsptr sptr, std::shared_ptr<std::unordered_set<Symsptr>> set) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
Symsptr integrand;
|
||||
Symsptr integrationConstant = sptrConstant(0.0);
|
||||
};
|
||||
}
|
||||
@@ -13,6 +13,7 @@
|
||||
|
||||
#include "Item.h"
|
||||
#include "System.h"
|
||||
#include "Symbolic.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include<algorithm>
|
||||
#include <memory>
|
||||
#include <typeinfo>
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include "LDUFullMat.h"
|
||||
|
||||
using namespace MbD;
|
||||
@@ -38,11 +38,11 @@ void LDUFullMat::forwardEliminateWithPivot(int p)
|
||||
//"Save factors in lower triangle for LU decomposition."
|
||||
|
||||
//| rowp app rowi aip factor |
|
||||
auto rowp = matrixA->at(p);
|
||||
auto& rowp = matrixA->at(p);
|
||||
auto app = rowp->at(p);
|
||||
for (int i = p + 1; i < m; i++)
|
||||
{
|
||||
auto rowi = matrixA->at(i);
|
||||
auto& rowi = matrixA->at(i);
|
||||
auto aip = rowi->at(p);
|
||||
auto factor = aip / app;
|
||||
rowi->at(p) = factor;
|
||||
@@ -138,9 +138,9 @@ void LDUFullMat::forwardSubstituteIntoL()
|
||||
auto vectorc = std::make_shared<FullColumn<double>>(n);
|
||||
for (int i = 0; i < n; i++)
|
||||
{
|
||||
auto rowi = matrixA->at(i);
|
||||
auto& rowi = matrixA->at(i);
|
||||
double sum = 0.0;
|
||||
for (int j = 0; j < i - 1; j++)
|
||||
for (int j = 0; j < i; j++)
|
||||
{
|
||||
sum += rowi->at(j) * vectorc->at(j);
|
||||
}
|
||||
@@ -155,11 +155,11 @@ void LDUFullMat::backSubstituteIntoDU()
|
||||
|
||||
//| rowi sum |
|
||||
answerX = std::make_shared<FullColumn<double>>(n);
|
||||
answerX->at(n - 1) = rightHandSideB->at(m - 1) / matrixA->at(m - 1)->at(n - 1);
|
||||
answerX->at((size_t)n - 1) = rightHandSideB->at((size_t)m - 1) / matrixA->at((size_t)m - 1)->at((size_t)n - 1);
|
||||
for (int i = n - 2; i >= 0; i--)
|
||||
{
|
||||
auto rowi = matrixA->at(i);
|
||||
double sum = answerX->at(n - 1) * rowi->at(n - 1);
|
||||
auto& rowi = matrixA->at(i);
|
||||
double sum = answerX->at((size_t)n - 1) * rowi->at((size_t)n - 1);
|
||||
for (int j = i + 1; j < n - 1; j++)
|
||||
{
|
||||
sum += answerX->at(j) * rowi->at(j);
|
||||
|
||||
@@ -5,5 +5,52 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#include "LinearMultiStepMethod.h"
|
||||
#include "FullColumn.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
FColDsptr MbD::LinearMultiStepMethod::derivativeatpresentpast(int n, double t, FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast)
|
||||
{
|
||||
//"Interpolate or extrapolate."
|
||||
//"dfdt(t) = df0dt + d2f0dt2*(t - t0) + d3f0dt3*(t - t0)^2 / 2! + ..."
|
||||
|
||||
auto answer = this->derivativepresentpast(n, y, ypast);
|
||||
if (t != time) {
|
||||
auto dt = t - time;
|
||||
auto dtpower = 1.0;
|
||||
for (int i = n + 1; i <= order; i++)
|
||||
{
|
||||
auto diydti = this->derivativepresentpast(i, y, ypast);
|
||||
dtpower = dtpower * dt;
|
||||
answer->equalSelfPlusFullColumntimes(diydti, dtpower * (OneOverFactorials->at((size_t)i - n)));
|
||||
}
|
||||
}
|
||||
return answer;
|
||||
}
|
||||
|
||||
FColDsptr MbD::LinearMultiStepMethod::derivativepresentpast(int order, FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast)
|
||||
{
|
||||
assert(false);
|
||||
return FColDsptr();
|
||||
}
|
||||
|
||||
double MbD::LinearMultiStepMethod::pvdotpv()
|
||||
{
|
||||
assert(false);
|
||||
return 0.0;
|
||||
}
|
||||
|
||||
double MbD::LinearMultiStepMethod::firstPastTimeNode()
|
||||
{
|
||||
return timeNodes->at(0);
|
||||
}
|
||||
|
||||
FColDsptr MbD::LinearMultiStepMethod::derivativepresentpastpresentDerivativepastDerivative(int n,
|
||||
FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast,
|
||||
FColDsptr ydot, std::shared_ptr<std::vector<FColDsptr>> ydotpast)
|
||||
{
|
||||
assert(false);
|
||||
return FColDsptr();
|
||||
}
|
||||
|
||||
@@ -5,17 +5,24 @@
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "DifferenceOperator.h"
|
||||
|
||||
namespace MbD {
|
||||
class LinearMultiStepMethod : public DifferenceOperator
|
||||
{
|
||||
//
|
||||
public:
|
||||
class LinearMultiStepMethod : public DifferenceOperator
|
||||
{
|
||||
//
|
||||
public:
|
||||
FColDsptr derivativeatpresentpast(int n, double t, FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast);
|
||||
virtual FColDsptr derivativepresentpast(int order, FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast);
|
||||
virtual double pvdotpv();
|
||||
double firstPastTimeNode();
|
||||
virtual FColDsptr derivativepresentpastpresentDerivativepastDerivative(int n,
|
||||
FColDsptr y, std::shared_ptr<std::vector<FColDsptr>> ypast,
|
||||
FColDsptr ydot, std::shared_ptr<std::vector<FColDsptr>> ydotpast);
|
||||
|
||||
};
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
@@ -18,3 +18,8 @@ double MbD::Ln::getValue()
|
||||
{
|
||||
return std::log(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::Ln::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<Ln>(arg);
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
Ln() = default;
|
||||
Ln(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::Log10::getValue()
|
||||
return std::log(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::Log10::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<Log10>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::Log10::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "lg(" << xx << ")";
|
||||
s << "lg(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
Log10() = default;
|
||||
Log10(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -19,8 +19,13 @@ double MbD::LogN::getValue()
|
||||
return std::log(xx->getValue());
|
||||
}
|
||||
|
||||
Symsptr MbD::LogN::copyWith(Symsptr arg)
|
||||
{
|
||||
return std::make_shared<LogN>(arg);
|
||||
}
|
||||
|
||||
std::ostream& MbD::LogN::printOn(std::ostream& s) const
|
||||
{
|
||||
s << "ln(" << xx << ")";
|
||||
s << "ln(" << *xx << ")";
|
||||
return s;
|
||||
}
|
||||
|
||||
@@ -18,6 +18,7 @@ namespace MbD {
|
||||
LogN() = default;
|
||||
LogN(Symsptr arg);
|
||||
double getValue() override;
|
||||
Symsptr copyWith(Symsptr arg) override;
|
||||
|
||||
std::ostream& printOn(std::ostream& s) const override;
|
||||
|
||||
|
||||
@@ -19,7 +19,7 @@ namespace MbD {
|
||||
void readInertiaMatrix(std::vector<std::string>& args);
|
||||
void createASMT() override;
|
||||
|
||||
std::string bodyString, name, nodeName;
|
||||
std::string bodyString, nodeName;
|
||||
double mass;
|
||||
FColDsptr rPcmP;
|
||||
FMatDsptr aJmat;
|
||||
|
||||
@@ -1,324 +1,324 @@
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749178 -0.09687939551894122 -3.252606517456513e-19 0.9999846242181696 -0.005545387925678226 0.09688088513829464 0.005519302327492587 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051885 0.9952948074630237 -0.001621407113303408 -0.09687939551894119 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.09688683977859862 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981437 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894111 2.168404344971009e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123014 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894122 -6.505213034913027e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749175 -0.09687939551894111 0 0.9999846242181696 -0.005545387925678225 0.09688088513829453 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 0.121 8.796847998598882e-19 0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 0.1853423520676719 -0.0003049963359123015 0.1415220993435272 0.9952959831601956 -0.0005372420906749176 -0.09687939551894122 -4.336808689942018e-19 0.9999846242181696 -0.005545387925678225 0.09688088513829464 0.005519302327492586 0.995280679706302 0 -0 -0 0 0 0
|
||||
3 0.3222616402245218 -0.0002911328660981436 0.1799682739051886 0.9952948074630237 -0.001621407113303408 -0.09687939551894117 0.001089272628257954 0.9999840309514423 -0.005545387925678226 0.0968868397785986 0.005413767734014727 0.995280679706302 0 0 0 0 0 0
|
||||
4 0.4640248981573186 -7.44074583944898e-17 0.1600000000000001 1 0 0 0 1 0 0 0 1 0 0 -0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975219 0.04313916854059263 2.168404344971009e-18 0.9993482542271943 -0.03609801619284766 -0.04316730264761665 0.03606436769945951 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124541 -0.009155819605617083 0.9990537652981445 -0.005530477486285016 0.04313916854059265 0.007090681752166227 0.9993230986318842 -0.03609801619284764 -0.04291032831253404 0.03636974511243224 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814532 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.469446951953614e-18 0.9993482542271943 -0.03609801619284765 -0.04316730264761659 0.0360643676994595 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.00553047748628502 0.04313916854059259 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253398 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975217 0.04313916854059247 -1.084202172485504e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761648 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285023 0.04313916854059251 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.0429103283125339 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975214 0.04313916854059258 5.204170427930421e-18 0.9993482542271943 -0.03609801619284765 -0.04316730264761659 0.0360643676994595 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059257 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253396 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975221 0.04313916854059258 -1.301042606982605e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124541 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059256 0.007090681752166228 0.9993230986318842 -0.03609801619284764 -0.04291032831253395 0.03636974511243224 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975222 0.04313916854059258 -1.517883041479706e-18 0.9993482542271943 -0.03609801619284768 -0.04316730264761659 0.03606436769945953 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285022 0.04313916854059257 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253396 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975214 0.04313916854059247 1.517883041479706e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761648 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617042 0.9990537652981445 -0.005530477486285025 0.04313916854059247 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253386 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975217 0.04313916854059252 2.168404344971009e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761653 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285023 0.04313916854059251 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253391 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.007090681752166231 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975217 0.04313916854059247 -1.084202172485504e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761648 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285022 0.04313916854059251 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.04291032831253391 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975215 0.04313916854059258 4.77048955893622e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059257 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253396 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975215 0.04313916854059252 2.168404344971009e-18 0.9993482542271943 -0.03609801619284766 -0.04316730264761653 0.03606436769945951 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059256 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253395 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975218 0.04313916854059258 1.301042606982605e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124541 -0.009155819605617069 0.9990537652981445 -0.00553047748628502 0.04313916854059258 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975219 0.04313916854059263 2.602085213965211e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761665 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617069 0.9990537652981445 -0.00553047748628502 0.0431391685405926 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.042910328312534 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.00155825398997522 0.04313916854059258 -4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.0431391685405926 0.007090681752166231 0.9993230986318842 -0.03609801619284766 -0.04291032831253399 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975219 0.04313916854059252 -8.673617379884035e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761653 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285022 0.04313916854059256 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253395 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.00155825398997522 0.04313916854059258 -4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419695 0.9990678575462876 0.001558253989975218 0.04313916854059252 0 0.9993482542271943 -0.03609801619284767 -0.04316730264761653 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059256 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253395 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975218 0.04313916854059263 3.469446951953614e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761665 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285019 0.0431391685405926 0.007090681752166229 0.9993230986318842 -0.03609801619284767 -0.04291032831253399 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975215 0.04313916854059258 4.336808689942018e-18 0.9993482542271943 -0.03609801619284765 -0.04316730264761659 0.0360643676994595 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124541 -0.009155819605617069 0.9990537652981445 -0.005530477486285019 0.04313916854059258 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.04291032831253398 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.001558253989975221 0.04313916854059263 8.673617379884035e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761665 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285019 0.04313916854059261 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.042910328312534 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.00155825398997522 0.04313916854059258 -4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059255 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419695 0.9990678575462876 0.00155825398997522 0.04313916854059263 1.734723475976807e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761665 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253398 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606623 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059252 8.673617379884035e-19 0.9993482542271943 -0.03609801619284768 -0.04316730264761653 0.03606436769945953 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285025 0.04313916854059252 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253391 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606623 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.818925648462312e-18 0.9993482542271943 -0.03609801619284768 -0.04316730264761659 0.03606436769945953 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617056 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284767 -0.04291032831253392 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419694 0.9990678575462876 0.001558253989975219 0.04313916854059252 -8.673617379884035e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761653 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285022 0.04313916854059253 0.00709068175216623 0.9993230986318842 -0.03609801619284767 -0.04291032831253393 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606623 -0.02810879162419696 0.9990678575462876 0.001558253989975221 0.04313916854059258 -6.505213034913027e-19 0.9993482542271943 -0.03609801619284768 -0.04316730264761659 0.03606436769945953 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059255 0.007090681752166228 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606623 -0.02810879162419696 0.9990678575462876 0.00155825398997522 0.04313916854059258 -4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.007090681752166231 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.001558253989975219 0.04313916854059252 -2.168404344971009e-19 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124543 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284767 -0.04291032831253393 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.035766082959412e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.00709068175216623 0.9993230986318842 -0.03609801619284767 -0.04291032831253394 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606623 -0.02810879162419696 0.9990678575462876 0.00155825398997522 0.04313916854059258 2.168404344971009e-19 0.9993482542271943 -0.03609801619284768 -0.04316730264761659 0.03606436769945953 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284767 -0.04291032831253397 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606623 -0.02810879162419694 0.9990678575462876 0.001558253989975219 0.04313916854059252 -8.673617379884035e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761653 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124543 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284767 -0.04291032831253393 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.00155825398997522 0.04313916854059258 -4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285021 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284767 -0.04291032831253394 0.03636974511243227 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975219 0.04313916854059258 4.336808689942018e-19 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202728 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975217 0.04313916854059258 2.168404344971009e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322783 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059258 0.00709068175216623 0.9993230986318842 -0.03609801619284766 -0.04291032831253397 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.04869259570202727 -0.001985390890606624 -0.02810879162419694 0.9990678575462876 0.00155825398997522 0.04313916854059252 -1.951563910473908e-18 0.9993482542271943 -0.03609801619284769 -0.04316730264761653 0.03606436769945954 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.09225341065322781 -0.001895145850124542 -0.009155819605617049 0.9990537652981445 -0.005530477486285024 0.04313916854059253 0.007090681752166232 0.9993230986318842 -0.03609801619284766 -0.04291032831253393 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
1 -0.121 -8.796847998598882e-19 -0.08 1 0 0 0 1 0 0 0 1 -0 -0 0 -0 0 0
|
||||
2 -0.0486925957020273 -0.001985390890606622 -0.02810879162419696 0.9990678575462876 0.001558253989975216 0.04313916854059258 3.903127820947816e-18 0.9993482542271943 -0.03609801619284767 -0.04316730264761659 0.03606436769945952 0.9984167192933857 0 -0 -0 0 0 0
|
||||
3 0.0922534106532278 -0.001895145850124542 -0.009155819605617063 0.9990537652981445 -0.005530477486285022 0.04313916854059255 0.007090681752166229 0.9993230986318842 -0.03609801619284766 -0.04291032831253394 0.03636974511243225 0.9984167192933857 0 0 0 0 0 -0
|
||||
4 0.2310424585814533 -7.816912863716824e-17 7.816912871471643e-17 1 0 0 0 1 0 0 0 1 0 0 0 0 0 0
|
||||
|
||||
297
OndselSolver/MBDynCase2.mbd
Normal file
297
OndselSolver/MBDynCase2.mbd
Normal file
@@ -0,0 +1,297 @@
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Data Block]
|
||||
|
||||
begin: data;
|
||||
problem: initial value;
|
||||
end: data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Problem Block]
|
||||
|
||||
begin: initial value;
|
||||
initial time: 0.0;
|
||||
final time: 3.0;
|
||||
time step: 0.01;
|
||||
max iterations: 100;
|
||||
tolerance: 1e-06;
|
||||
derivatives tolerance: 0.0001;
|
||||
derivatives max iterations: 100;
|
||||
derivatives coefficient: auto;
|
||||
end: initial value;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Control Data Block]
|
||||
|
||||
begin: control data;
|
||||
max iterations: 1000;
|
||||
default orientation: euler321;
|
||||
omega rotates: no;
|
||||
print: none;
|
||||
initial stiffness: 1.0, 1.0;
|
||||
structural nodes: 4;
|
||||
rigid bodies: 3;
|
||||
joints: 6;
|
||||
end: control data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Design Variables]
|
||||
|
||||
#Generic bodies
|
||||
|
||||
#body: 2
|
||||
set: integer body_2 = 2; #body label
|
||||
set: real mass_2 = 1.448636188351172; #mass [kg]
|
||||
set: real volume_2 = 0.00018337166941154076; #volume [m^3]
|
||||
|
||||
#body: 3
|
||||
set: integer body_3 = 3; #body label
|
||||
set: real mass_3 = 2.8529486557067685; #mass [kg]
|
||||
set: real volume_3 = 0.0003611327412287049; #volume [m^3]
|
||||
|
||||
#body: 4
|
||||
set: integer body_4 = 4; #body label
|
||||
set: real mass_4 = 10.859427202622141; #mass [kg]
|
||||
set: real volume_4 = 0.0013746110383066003; #volume [m^3]
|
||||
|
||||
#Nodes
|
||||
|
||||
#node: 1
|
||||
set: integer structural_node_1 = 1; #node label
|
||||
|
||||
#node: 2
|
||||
set: integer structural_node_2 = 2; #node label
|
||||
|
||||
#node: 3
|
||||
set: integer structural_node_3 = 3; #node label
|
||||
|
||||
#node: 4
|
||||
set: integer structural_node_4 = 4; #node label
|
||||
|
||||
#Joints
|
||||
|
||||
#joint: 1
|
||||
set: integer joint_1 = 1; #joint label
|
||||
|
||||
#joint: 2
|
||||
set: integer joint_2 = 2; #joint label
|
||||
|
||||
#joint: 3
|
||||
set: integer joint_3 = 3; #joint label
|
||||
|
||||
#joint: 4
|
||||
set: integer joint_4 = 4; #joint label
|
||||
|
||||
#joint: 5
|
||||
set: integer joint_5 = 5; #joint label
|
||||
|
||||
#joint: 6
|
||||
set: integer joint_6 = 6; #joint label
|
||||
|
||||
#Nodes: initial conditions
|
||||
|
||||
#node: 1
|
||||
set: real Px_1 = -0.121; #X component of the absolute position [m]
|
||||
set: real Py_1 = -1.218180697837851e-18; #Y component of the absolute position [m]
|
||||
set: real Pz_1 = -0.08; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_1 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_1 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_1 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_1 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_1 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_1 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 2
|
||||
set: real Px_2 = -0.047537048944738425; #X component of the absolute position [m]
|
||||
set: real Py_2 = 0.09742200410568831; #Y component of the absolute position [m]
|
||||
set: real Pz_2 = -0.030293476812230588; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_2 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_2 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_2 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_2 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_2 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_2 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 3
|
||||
set: real Px_3 = 0.07099630277370235; #X component of the absolute position [m]
|
||||
set: real Py_3 = -0.07364765799707981; #Y component of the absolute position [m]
|
||||
set: real Pz_3 = 0.058407900823760565; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_3 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_3 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_3 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_3 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_3 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_3 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 4
|
||||
set: real Px_4 = 0.3723079639890564; #X component of the absolute position [m]
|
||||
set: real Py_4 = 0.04333150035096042; #Y component of the absolute position [m]
|
||||
set: real Pz_4 = 0.008140985321785409; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_4 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_4 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_4 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_4 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_4 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_4 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Intermediate Variables]
|
||||
|
||||
#Moments of inertia and relative center of mass
|
||||
|
||||
#body 2:
|
||||
set: real Ixx_2 = 0.0028717510150880004; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_2 = 0.002864447840812; #moment of inertia [kg*m^2]
|
||||
set: real Izz_2 = 0.0007089594589930001; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_2 = 7.105427357601002e-18; #X component of the relative center of mass [m]
|
||||
set: real Ry_2 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_2 = 7.105427357601002e-18; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 3:
|
||||
set: real Ixx_3 = 0.033837921987970004; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_3 = 0.033715148099504; #moment of inertia [kg*m^2]
|
||||
set: real Izz_3 = 0.001956310318013; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_3 = 2.842170943040401e-17; #X component of the relative center of mass [m]
|
||||
set: real Ry_3 = -1.4210854715202004e-17; #Y component of the relative center of mass [m]
|
||||
set: real Rz_3 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 4:
|
||||
set: real Ixx_4 = 0.07706742098794901; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_4 = 0.066351815798527; #moment of inertia [kg*m^2]
|
||||
set: real Izz_4 = 0.061792350456255; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_4 = 2.842170943040401e-16; #X component of the relative center of mass [m]
|
||||
set: real Ry_4 = 2.1316282072803006e-17; #Y component of the relative center of mass [m]
|
||||
set: real Rz_4 = 2.2737367544323206e-16; #Z component of the relative center of mass [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Nodes Block]
|
||||
|
||||
begin: nodes;
|
||||
|
||||
structural: structural_node_1,
|
||||
static,
|
||||
Px_1, Py_1, Pz_1, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_1, Vy_1, Vz_1, #<absolute_velocity> [m/s]
|
||||
Wx_1, Wy_1, Wz_1; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_2,
|
||||
dynamic,
|
||||
Px_2, Py_2, Pz_2, #<absolute_position> [m]
|
||||
3, 0.28116838555915347, -0.12674940821214617, 0.9512512425641977, 2, -0.12674940821214617, 0.9776506595433675, 0.16773125949652098, #<absolute_orientation_matrix>
|
||||
Vx_2, Vy_2, Vz_2, #<absolute_velocity> [m/s]
|
||||
Wx_2, Wy_2, Wz_2; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_3,
|
||||
dynamic,
|
||||
Px_3, Py_3, Pz_3, #<absolute_position> [m]
|
||||
3, -0.27178893568691503, -0.25783416049630004, 0.9271743741709766, 2, 0.014330116918634624, 0.9622501868990581, 0.271788935686915, #<absolute_orientation_matrix>
|
||||
Vx_3, Vy_3, Vz_3, #<absolute_velocity> [m/s]
|
||||
Wx_3, Wy_3, Wz_3; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_4,
|
||||
dynamic,
|
||||
Px_4, Py_4, Pz_4, #<absolute_position> [m]
|
||||
3, 0.2588190451025211, 0.0, 0.9659258262890682, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_4, Vy_4, Vz_4, #<absolute_velocity> [m/s]
|
||||
Wx_4, Wy_4, Wz_4; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
end: nodes;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Elements Block]
|
||||
|
||||
begin: elements;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Bodies]
|
||||
|
||||
body: body_2,
|
||||
structural_node_2, #<node_label>
|
||||
mass_2, #<mass> [kg]
|
||||
Rx_2, Ry_2, Rz_2, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_2, Iyy_2, Izz_2, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.0054384608129255385, 0.8559103374577453, 0.5150405937686557, 2, 0.9969290667160357, -0.0024978913689130133, 0.0023196850194898005;
|
||||
|
||||
body: body_3,
|
||||
structural_node_3, #<node_label>
|
||||
mass_3, #<mass> [kg]
|
||||
Rx_3, Ry_3, Rz_3, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_3, Iyy_3, Izz_3, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.9973238325492868, 0.0012847690482160057, -0.002629529780301787, 2, -0.00011328308715380375, 1.0027304733964244, 0.004450235157436283;
|
||||
|
||||
body: body_4,
|
||||
structural_node_4, #<node_label>
|
||||
mass_4, #<mass> [kg]
|
||||
Rx_4, Ry_4, Rz_4, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_4, Iyy_4, Izz_4, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -8.551421488581235e-05, 0.0, 0.9957768995806164, 2, 0.0, 1.0, 0.0;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Joints]
|
||||
|
||||
joint: joint_1,
|
||||
clamp,
|
||||
structural_node_1, #<node_label>
|
||||
-0.121, -1.218180697837851e-18, -0.08, #<absolute_pin_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_2,
|
||||
axial rotation,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.0, 1.218180697837851e-18, 0.05, #<relative_offset_1> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<relative_orientation_matrix_1>
|
||||
structural_node_2, #<node_2_label>
|
||||
-0.03739853284269051, 0.0, 0.0032867622552210634, #<relative_offset_2> [m]
|
||||
orientation, 3, 5.204170427930421e-18, 0.0, 1.0, 2, guess, #<relative_orientation_matrix_2>
|
||||
string, "model::drive(1, Time)"; #<angular_velocity> [rad/s]
|
||||
|
||||
joint: joint_3,
|
||||
revolute hinge,
|
||||
structural_node_2, #<node_1_label>
|
||||
0.03260146715730949, 1.4210854715202004e-17, 0.05328676225522106, #<relative_position_1> [m]
|
||||
orientation, 3, 5.204170427930421e-18, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_3, #<node_2_label>
|
||||
-0.1400000000000079, -1.0444978215673472e-15, 0.024999999999998038, #<relative_position_2> [m]
|
||||
orientation, 3, -5.551115123125784e-17, -5.984795992119986e-17, 1.0, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_4,
|
||||
in line,
|
||||
structural_node_3, #<node_1_label>
|
||||
0.13999999999999133, 4.4231285301066236e-16, 9.79127889877418e-15, #<relative_line_position> [m]
|
||||
3, 2.7195091690402506e-15, 1.2586758486779817e-14, 1.0, 2, 0.6882367162699149, 0.7254861972346578, -1.1003185610451133e-14, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, -0.045580834634119244, -2.0299354019925886e-10, 1.2562251640702015e-08; #<relative_offset> [m]
|
||||
|
||||
joint: joint_5,
|
||||
in line,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.0, 1.2181806978377854e-18, 0.08, #<relative_line_position> [m]
|
||||
3, 1.0, -2.220446049250313e-16, 2.220446049250313e-16, 2, -2.220446049250313e-16, 0.0, 1.0, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, -0.045580834634119244, -2.0299354019925886e-10, 1.2562251640702015e-08; #<relative_offset> [m]
|
||||
|
||||
joint: joint_6,
|
||||
prismatic,
|
||||
structural_node_1, #<node_1_label>
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #relative_orientation_matrix_1>
|
||||
structural_node_4, #<node_2_label>
|
||||
orientation, 3, 0, 0, 1, 2, 0, 1, 0; #relative_orientation_matrix_2>
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Drive callers]
|
||||
|
||||
drive caller: 1, name,"drive:1", ramp, 6.28, 0.0, 1.0, 0.0;
|
||||
|
||||
end: elements;
|
||||
|
||||
1204
OndselSolver/MBDynCase2.mov
Normal file
1204
OndselSolver/MBDynCase2.mov
Normal file
File diff suppressed because it is too large
Load Diff
297
OndselSolver/MBDynCase2orig.mbd
Normal file
297
OndselSolver/MBDynCase2orig.mbd
Normal file
@@ -0,0 +1,297 @@
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Data Block]
|
||||
|
||||
begin: data;
|
||||
problem: initial value;
|
||||
end: data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Problem Block]
|
||||
|
||||
begin: initial value;
|
||||
initial time: 0.0;
|
||||
final time: 8.0;
|
||||
time step: 0.01;
|
||||
max iterations: 100;
|
||||
tolerance: 1e-06;
|
||||
derivatives tolerance: 0.0001;
|
||||
derivatives max iterations: 100;
|
||||
derivatives coefficient: auto;
|
||||
end: initial value;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Control Data Block]
|
||||
|
||||
begin: control data;
|
||||
max iterations: 1000;
|
||||
default orientation: euler321;
|
||||
omega rotates: no;
|
||||
print: none;
|
||||
initial stiffness: 1.0, 1.0;
|
||||
structural nodes: 4;
|
||||
rigid bodies: 3;
|
||||
joints: 6;
|
||||
end: control data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Design Variables]
|
||||
|
||||
#Generic bodies
|
||||
|
||||
#body: 2
|
||||
set: integer body_2 = 2; #body label
|
||||
set: real mass_2 = 1.448636188351172; #mass [kg]
|
||||
set: real volume_2 = 0.00018337166941154076; #volume [m^3]
|
||||
|
||||
#body: 3
|
||||
set: integer body_3 = 3; #body label
|
||||
set: real mass_3 = 2.8529486557067685; #mass [kg]
|
||||
set: real volume_3 = 0.0003611327412287049; #volume [m^3]
|
||||
|
||||
#body: 4
|
||||
set: integer body_4 = 4; #body label
|
||||
set: real mass_4 = 10.859427202622141; #mass [kg]
|
||||
set: real volume_4 = 0.0013746110383066003; #volume [m^3]
|
||||
|
||||
#Nodes
|
||||
|
||||
#node: 1
|
||||
set: integer structural_node_1 = 1; #node label
|
||||
|
||||
#node: 2
|
||||
set: integer structural_node_2 = 2; #node label
|
||||
|
||||
#node: 3
|
||||
set: integer structural_node_3 = 3; #node label
|
||||
|
||||
#node: 4
|
||||
set: integer structural_node_4 = 4; #node label
|
||||
|
||||
#Joints
|
||||
|
||||
#joint: 1
|
||||
set: integer joint_1 = 1; #joint label
|
||||
|
||||
#joint: 2
|
||||
set: integer joint_2 = 2; #joint label
|
||||
|
||||
#joint: 3
|
||||
set: integer joint_3 = 3; #joint label
|
||||
|
||||
#joint: 4
|
||||
set: integer joint_4 = 4; #joint label
|
||||
|
||||
#joint: 5
|
||||
set: integer joint_5 = 5; #joint label
|
||||
|
||||
#joint: 6
|
||||
set: integer joint_6 = 6; #joint label
|
||||
|
||||
#Nodes: initial conditions
|
||||
|
||||
#node: 1
|
||||
set: real Px_1 = -0.121; #X component of the absolute position [m]
|
||||
set: real Py_1 = -1.218180697837851e-18; #Y component of the absolute position [m]
|
||||
set: real Pz_1 = -0.08; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_1 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_1 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_1 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_1 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_1 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_1 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 2
|
||||
set: real Px_2 = -0.047537048944738425; #X component of the absolute position [m]
|
||||
set: real Py_2 = 0.09742200410568831; #Y component of the absolute position [m]
|
||||
set: real Pz_2 = -0.030293476812230588; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_2 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_2 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_2 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_2 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_2 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_2 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 3
|
||||
set: real Px_3 = 0.07099630277370235; #X component of the absolute position [m]
|
||||
set: real Py_3 = -0.07364765799707981; #Y component of the absolute position [m]
|
||||
set: real Pz_3 = 0.058407900823760565; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_3 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_3 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_3 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_3 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_3 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_3 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 4
|
||||
set: real Px_4 = 0.3723079639890564; #X component of the absolute position [m]
|
||||
set: real Py_4 = 0.04333150035096042; #Y component of the absolute position [m]
|
||||
set: real Pz_4 = 0.008140985321785409; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_4 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_4 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_4 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_4 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_4 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_4 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Intermediate Variables]
|
||||
|
||||
#Moments of inertia and relative center of mass
|
||||
|
||||
#body 2:
|
||||
set: real Ixx_2 = 0.0028717510150880004; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_2 = 0.002864447840812; #moment of inertia [kg*m^2]
|
||||
set: real Izz_2 = 0.0007089594589930001; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_2 = 7.105427357601002e-18; #X component of the relative center of mass [m]
|
||||
set: real Ry_2 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_2 = 7.105427357601002e-18; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 3:
|
||||
set: real Ixx_3 = 0.033837921987970004; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_3 = 0.033715148099504; #moment of inertia [kg*m^2]
|
||||
set: real Izz_3 = 0.001956310318013; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_3 = 2.842170943040401e-17; #X component of the relative center of mass [m]
|
||||
set: real Ry_3 = -1.4210854715202004e-17; #Y component of the relative center of mass [m]
|
||||
set: real Rz_3 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 4:
|
||||
set: real Ixx_4 = 0.07706742098794901; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_4 = 0.066351815798527; #moment of inertia [kg*m^2]
|
||||
set: real Izz_4 = 0.061792350456255; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_4 = 2.842170943040401e-16; #X component of the relative center of mass [m]
|
||||
set: real Ry_4 = 2.1316282072803006e-17; #Y component of the relative center of mass [m]
|
||||
set: real Rz_4 = 2.2737367544323206e-16; #Z component of the relative center of mass [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Nodes Block]
|
||||
|
||||
begin: nodes;
|
||||
|
||||
structural: structural_node_1,
|
||||
static,
|
||||
Px_1, Py_1, Pz_1, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_1, Vy_1, Vz_1, #<absolute_velocity> [m/s]
|
||||
Wx_1, Wy_1, Wz_1; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_2,
|
||||
dynamic,
|
||||
Px_2, Py_2, Pz_2, #<absolute_position> [m]
|
||||
3, 0.28116838555915347, -0.12674940821214617, 0.9512512425641977, 2, -0.12674940821214617, 0.9776506595433675, 0.16773125949652098, #<absolute_orientation_matrix>
|
||||
Vx_2, Vy_2, Vz_2, #<absolute_velocity> [m/s]
|
||||
Wx_2, Wy_2, Wz_2; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_3,
|
||||
dynamic,
|
||||
Px_3, Py_3, Pz_3, #<absolute_position> [m]
|
||||
3, -0.27178893568691503, -0.25783416049630004, 0.9271743741709766, 2, 0.014330116918634624, 0.9622501868990581, 0.271788935686915, #<absolute_orientation_matrix>
|
||||
Vx_3, Vy_3, Vz_3, #<absolute_velocity> [m/s]
|
||||
Wx_3, Wy_3, Wz_3; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_4,
|
||||
dynamic,
|
||||
Px_4, Py_4, Pz_4, #<absolute_position> [m]
|
||||
3, 0.2588190451025211, 0.0, 0.9659258262890682, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_4, Vy_4, Vz_4, #<absolute_velocity> [m/s]
|
||||
Wx_4, Wy_4, Wz_4; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
end: nodes;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Elements Block]
|
||||
|
||||
begin: elements;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Bodies]
|
||||
|
||||
body: body_2,
|
||||
structural_node_2, #<node_label>
|
||||
mass_2, #<mass> [kg]
|
||||
Rx_2, Ry_2, Rz_2, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_2, Iyy_2, Izz_2, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.0054384608129255385, 0.8559103374577453, 0.5150405937686557, 2, 0.9969290667160357, -0.0024978913689130133, 0.0023196850194898005;
|
||||
|
||||
body: body_3,
|
||||
structural_node_3, #<node_label>
|
||||
mass_3, #<mass> [kg]
|
||||
Rx_3, Ry_3, Rz_3, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_3, Iyy_3, Izz_3, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.9973238325492868, 0.0012847690482160057, -0.002629529780301787, 2, -0.00011328308715380375, 1.0027304733964244, 0.004450235157436283;
|
||||
|
||||
body: body_4,
|
||||
structural_node_4, #<node_label>
|
||||
mass_4, #<mass> [kg]
|
||||
Rx_4, Ry_4, Rz_4, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_4, Iyy_4, Izz_4, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -8.551421488581235e-05, 0.0, 0.9957768995806164, 2, 0.0, 1.0, 0.0;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Joints]
|
||||
|
||||
joint: joint_1,
|
||||
clamp,
|
||||
structural_node_1, #<node_label>
|
||||
-0.121, -1.218180697837851e-18, -0.08, #<absolute_pin_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_2,
|
||||
axial rotation,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.0, 1.218180697837851e-18, 0.05, #<relative_offset_1> [m]
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<relative_orientation_matrix_1>
|
||||
structural_node_2, #<node_2_label>
|
||||
-0.03739853284269051, 0.0, 0.0032867622552210634, #<relative_offset_2> [m]
|
||||
orientation, 3, 5.204170427930421e-18, 0.0, 1.0, 2, guess, #<relative_orientation_matrix_2>
|
||||
string, "model::drive(1, Time)"; #<angular_velocity> [rad/s]
|
||||
|
||||
joint: joint_3,
|
||||
revolute hinge,
|
||||
structural_node_2, #<node_1_label>
|
||||
0.03260146715730949, 1.4210854715202004e-17, 0.05328676225522106, #<relative_position_1> [m]
|
||||
orientation, 3, 5.204170427930421e-18, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_3, #<node_2_label>
|
||||
-0.1400000000000079, -1.0444978215673472e-15, 0.024999999999998038, #<relative_position_2> [m]
|
||||
orientation, 3, -5.551115123125784e-17, -5.984795992119986e-17, 1.0, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_4,
|
||||
in line,
|
||||
structural_node_3, #<node_1_label>
|
||||
0.13999999999999133, 4.4231285301066236e-16, 9.79127889877418e-15, #<relative_line_position> [m]
|
||||
3, 2.7195091690402506e-15, 1.2586758486779817e-14, 1.0, 2, 0.6882367162699149, 0.7254861972346578, -1.1003185610451133e-14, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, -0.045580834634119244, -2.0299354019925886e-10, 1.2562251640702015e-08; #<relative_offset> [m]
|
||||
|
||||
joint: joint_5,
|
||||
in line,
|
||||
structural_node_1, #<node_1_label>
|
||||
0.0, 1.2181806978377854e-18, 0.08, #<relative_line_position> [m]
|
||||
3, 1.0, -2.220446049250313e-16, 2.220446049250313e-16, 2, -2.220446049250313e-16, 0.0, 1.0, #<relative_orientation>
|
||||
structural_node_4, #<node_2_label>
|
||||
offset, -0.045580834634119244, -2.0299354019925886e-10, 1.2562251640702015e-08; #<relative_offset> [m]
|
||||
|
||||
joint: joint_6,
|
||||
prismatic,
|
||||
structural_node_1, #<node_1_label>
|
||||
orientation, 3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #relative_orientation_matrix_1>
|
||||
structural_node_4, #<node_2_label>
|
||||
orientation, 3, 0, 0, 1, 2, 0, 1, 0; #relative_orientation_matrix_2>
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Drive callers]
|
||||
|
||||
drive caller: 1, name,"drive:1", ramp, 6.28, 0.0, 1.0, 0.0;
|
||||
|
||||
end: elements;
|
||||
|
||||
3208
OndselSolver/MBDynCase2orig.mov
Normal file
3208
OndselSolver/MBDynCase2orig.mov
Normal file
File diff suppressed because it is too large
Load Diff
321
OndselSolver/MBDynCaseDebug1.mbd
Normal file
321
OndselSolver/MBDynCaseDebug1.mbd
Normal file
@@ -0,0 +1,321 @@
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Data Block]
|
||||
|
||||
begin: data;
|
||||
problem: initial value;
|
||||
end: data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Problem Block]
|
||||
|
||||
begin: initial value;
|
||||
initial time: 0.0;
|
||||
final time: 8.0;
|
||||
time step: 0.01;
|
||||
max iterations: 100;
|
||||
tolerance: 1e-06;
|
||||
derivatives tolerance: 0.0001;
|
||||
derivatives max iterations: 100;
|
||||
derivatives coefficient: auto;
|
||||
end: initial value;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Control Data Block]
|
||||
|
||||
begin: control data;
|
||||
max iterations: 1000;
|
||||
default orientation: orientation matrix;
|
||||
omega rotates: no;
|
||||
print: none;
|
||||
initial stiffness: 1.0, 1.0;
|
||||
structural nodes: 5;
|
||||
rigid bodies: 3;
|
||||
joints: 6;
|
||||
end: control data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Design Variables]
|
||||
|
||||
#Generic bodies
|
||||
|
||||
#body: 2
|
||||
set: integer body_2 = 2; #body label
|
||||
set: real mass_2 = 0.24147734685710437; #mass [kg]
|
||||
set: real volume_2 = 3.056675276672207e-05; #volume [m^3]
|
||||
|
||||
#body: 4
|
||||
set: integer body_4 = 4; #body label
|
||||
set: real mass_4 = 0.11253654770310718; #mass [kg]
|
||||
set: real volume_4 = 1.4245132620646478e-05; #volume [m^3]
|
||||
|
||||
#body: 5
|
||||
set: integer body_5 = 5; #body label
|
||||
set: real mass_5 = 0.11253654770310723; #mass [kg]
|
||||
set: real volume_5 = 1.4245132620646483e-05; #volume [m^3]
|
||||
|
||||
#Nodes
|
||||
|
||||
#node: 1
|
||||
set: integer structural_node_1 = 1; #node label
|
||||
|
||||
#node: 2
|
||||
set: integer structural_node_2 = 2; #node label
|
||||
|
||||
#node: 3
|
||||
set: integer structural_node_3 = 3; #node label
|
||||
|
||||
#node: 4
|
||||
set: integer structural_node_4 = 4; #node label
|
||||
|
||||
#node: 5
|
||||
set: integer structural_node_5 = 5; #node label
|
||||
|
||||
#Joints
|
||||
|
||||
#joint: 1
|
||||
set: integer joint_1 = 1; #joint label
|
||||
|
||||
#joint: 2
|
||||
set: integer joint_2 = 2; #joint label
|
||||
|
||||
#joint: 3
|
||||
set: integer joint_3 = 3; #joint label
|
||||
|
||||
#joint: 4
|
||||
set: integer joint_4 = 4; #joint label
|
||||
|
||||
#joint: 5
|
||||
set: integer joint_5 = 5; #joint label
|
||||
|
||||
#joint: 7
|
||||
set: integer joint_7 = 7; #joint label
|
||||
|
||||
#Nodes: initial conditions
|
||||
|
||||
#node: 1
|
||||
set: real Px_1 = 0.16912189837562464; #X component of the absolute position [m]
|
||||
set: real Py_1 = -0.10055206743263254; #Y component of the absolute position [m]
|
||||
set: real Pz_1 = 0.07867737409397452; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_1 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_1 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_1 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_1 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_1 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_1 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 2
|
||||
set: real Px_2 = 0.018683478687078307; #X component of the absolute position [m]
|
||||
set: real Py_2 = -0.05533171845235879; #Y component of the absolute position [m]
|
||||
set: real Pz_2 = 0.1768528076947657; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_2 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_2 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_2 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_2 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_2 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_2 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 3
|
||||
set: real Px_3 = 0.2890983348369078; #X component of the absolute position [m]
|
||||
set: real Py_3 = -0.06156645049450425; #Y component of the absolute position [m]
|
||||
set: real Pz_3 = 0.09724597715885096; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_3 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_3 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_3 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_3 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_3 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_3 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 4
|
||||
set: real Px_4 = 0.11637356459110539; #X component of the absolute position [m]
|
||||
set: real Py_4 = -0.019655254070140387; #Y component of the absolute position [m]
|
||||
set: real Pz_4 = 0.20651079866339145; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_4 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_4 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_4 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_4 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_4 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_4 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 5
|
||||
set: real Px_5 = 0.15064540729834192; #X component of the absolute position [m]
|
||||
set: real Py_5 = -0.020536937096322302; #Y component of the absolute position [m]
|
||||
set: real Pz_5 = 0.06548008210568429; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_5 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_5 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_5 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_5 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_5 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_5 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Intermediate Variables]
|
||||
|
||||
#Moments of inertia and relative center of mass
|
||||
|
||||
#body 2:
|
||||
set: real Ixx_2 = 6.927961737800001e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_2 = 5.6689424982e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_2 = 2.9053392577e-05; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_2 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_2 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_2 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 4:
|
||||
set: real Ixx_4 = 7.9157004521e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_4 = 7.769349168e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_4 = 3.339121993e-06; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_4 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_4 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_4 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 5:
|
||||
set: real Ixx_5 = 7.9157004521e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_5 = 7.769349168e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_5 = 3.339121993e-06; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_5 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_5 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_5 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Nodes Block]
|
||||
|
||||
begin: nodes;
|
||||
|
||||
structural: structural_node_1,
|
||||
static,
|
||||
Px_1, Py_1, Pz_1, #<absolute_position> [m]
|
||||
3, -0.3539135011019427, 0.9158836712023025, 0.18947911379030236, 2, -0.5084786583487672, -0.018385530501657588, -0.8608782877224926, #<absolute_orientation_matrix>
|
||||
Vx_1, Vy_1, Vz_1, #<absolute_velocity> [m/s]
|
||||
Wx_1, Wy_1, Wz_1; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_2,
|
||||
dynamic,
|
||||
Px_2, Py_2, Pz_2, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_2, Vy_2, Vz_2, #<absolute_velocity> [m/s]
|
||||
Wx_2, Wy_2, Wz_2; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_3,
|
||||
static,
|
||||
Px_3, Py_3, Pz_3, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_3, Vy_3, Vz_3, #<absolute_velocity> [m/s]
|
||||
Wx_3, Wy_3, Wz_3; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_4,
|
||||
dynamic,
|
||||
Px_4, Py_4, Pz_4, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_4, Vy_4, Vz_4, #<absolute_velocity> [m/s]
|
||||
Wx_4, Wy_4, Wz_4; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_5,
|
||||
dynamic,
|
||||
Px_5, Py_5, Pz_5, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_5, Vy_5, Vz_5, #<absolute_velocity> [m/s]
|
||||
Wx_5, Wy_5, Wz_5; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
end: nodes;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Elements Block]
|
||||
|
||||
begin: elements;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Bodies]
|
||||
|
||||
body: body_2,
|
||||
structural_node_2, #<node_label>
|
||||
mass_2, #<mass> [kg]
|
||||
Rx_2, Ry_2, Rz_2, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_2, Iyy_2, Izz_2, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.35, 0.91, 0.21, 2, 0.78, 0.4, -0.47;
|
||||
|
||||
body: body_4,
|
||||
structural_node_4, #<node_label>
|
||||
mass_4, #<mass> [kg]
|
||||
Rx_4, Ry_4, Rz_4, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_4, Iyy_4, Izz_4, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.78, 0.4, -0.47, 2, -0.36, 0.91, 0.19;
|
||||
|
||||
body: body_5,
|
||||
structural_node_5, #<node_label>
|
||||
mass_5, #<mass> [kg]
|
||||
Rx_5, Ry_5, Rz_5, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_5, Iyy_5, Izz_5, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.36, 0.91, 0.19, 2, 0.78, 0.4, -0.47;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Joints]
|
||||
|
||||
joint: joint_1,
|
||||
clamp,
|
||||
structural_node_1, #<node_label>
|
||||
0.16912189837562464, -0.10055206743263254, 0.07867737409397452, #<absolute_pin_position> [m]
|
||||
3, -0.3539135011019427, 0.9158836712023025, 0.18947911379030236, 2, -0.5084786583487672, -0.018385530501657588, -0.8608782877224926; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_2,
|
||||
axial rotation,
|
||||
structural_node_1, #<node_1_label>
|
||||
1.0407603667772492e-11, -0.05247682460581396, -0.00025357557055826873, #<relative_offset_1> [m]
|
||||
orientation, 3, 1.1102230246251565e-16, -1.0, 0.0, 2, guess, #<relative_orientation_matrix_1>
|
||||
structural_node_2, #<node_2_label>
|
||||
0.006998226646402806, -0.00490348349806041, 0.007426083408032554, #<relative_offset_2> [m]
|
||||
orientation, 3, 0.5084786344413901, 0.01838554762064229, 0.8608783014778036, 2, guess, #<relative_orientation_matrix_2>
|
||||
string, "model::drive(1, Time)"; #<angular_velocity> [rad/s]
|
||||
|
||||
joint: joint_3,
|
||||
clamp,
|
||||
structural_node_3, #<node_label>
|
||||
0.2890983348369078, -0.06156645049450425, 0.09724597715885096, #<absolute_pin_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_4,
|
||||
revolute hinge,
|
||||
structural_node_2, #<node_1_label>
|
||||
-0.0011629534118987692, 0.02262071327533141, 0.01746668757489371, #<relative_position_1> [m]
|
||||
orientation, 3, 0.5084786344412178, 0.018385547620640152, 0.8608783014779054, 2, guess, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_4, #<node_2_label>
|
||||
-0.031347177833029705, -0.01617494903756937, 0.018860685712244078, #<relative_position_2> [m]
|
||||
orientation, 3, 0.5084786455601428, 0.018385495401303797, 0.860878296025734, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_5,
|
||||
revolute hinge,
|
||||
structural_node_4, #<node_1_label>
|
||||
0.03388957106083931, 0.016266876514581658, -0.01455629423212079, #<relative_position_1> [m]
|
||||
orientation, 3, 0.50847864556046, 0.0183854954014063, 0.8608782960255446, 2, guess, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_5, #<node_2_label>
|
||||
-0.016813818553224735, 0.036484433510506876, 0.003343892503690739, #<relative_position_2> [m]
|
||||
orientation, 3, 0.5084787180221569, 0.01838550036990011, 0.8608782531198544, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_7,
|
||||
revolute hinge,
|
||||
structural_node_3, #<node_1_label>
|
||||
1.1368683772161603e-16, 0.0, -1.4210854715202004e-17, #<relative_position_1> [m]
|
||||
orientation, 3, 0.5094306516594838, 0.018659363391322903, 0.8603093858070039, 2, guess, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_5, #<node_2_label>
|
||||
0.014271424963118534, -0.03657636101236503, -0.007648283769292526, #<relative_position_2> [m]
|
||||
orientation, 3, 0.5084787180221835, 0.018385500369866165, 0.8608782531198396, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Drive callers]
|
||||
|
||||
drive caller: 1, name,"drive:1", ramp, 5.0, 0.25, 4.0, 0.0;
|
||||
|
||||
end: elements;
|
||||
|
||||
4005
OndselSolver/MBDynCaseDebug1.mov
Normal file
4005
OndselSolver/MBDynCaseDebug1.mov
Normal file
File diff suppressed because it is too large
Load Diff
320
OndselSolver/MBDynCaseDebug2.mbd
Normal file
320
OndselSolver/MBDynCaseDebug2.mbd
Normal file
@@ -0,0 +1,320 @@
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Data Block]
|
||||
|
||||
begin: data;
|
||||
problem: initial value;
|
||||
end: data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Problem Block]
|
||||
|
||||
begin: initial value;
|
||||
initial time: 0.0;
|
||||
final time: 8.0;
|
||||
time step: 0.01;
|
||||
max iterations: 100;
|
||||
tolerance: 1e-06;
|
||||
derivatives tolerance: 0.0001;
|
||||
derivatives max iterations: 100;
|
||||
derivatives coefficient: auto;
|
||||
end: initial value;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Control Data Block]
|
||||
|
||||
begin: control data;
|
||||
max iterations: 1000;
|
||||
default orientation: orientation matrix;
|
||||
omega rotates: no;
|
||||
print: none;
|
||||
initial stiffness: 1.0, 1.0;
|
||||
structural nodes: 5;
|
||||
rigid bodies: 3;
|
||||
joints: 6;
|
||||
end: control data;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Design Variables]
|
||||
|
||||
#Generic bodies
|
||||
|
||||
#body: 2
|
||||
set: integer body_2 = 2; #body label
|
||||
set: real mass_2 = 0.24147734685710437; #mass [kg]
|
||||
set: real volume_2 = 3.056675276672207e-05; #volume [m^3]
|
||||
|
||||
#body: 4
|
||||
set: integer body_4 = 4; #body label
|
||||
set: real mass_4 = 0.11253654770310718; #mass [kg]
|
||||
set: real volume_4 = 1.4245132620646478e-05; #volume [m^3]
|
||||
|
||||
#body: 5
|
||||
set: integer body_5 = 5; #body label
|
||||
set: real mass_5 = 0.11253654770310723; #mass [kg]
|
||||
set: real volume_5 = 1.4245132620646483e-05; #volume [m^3]
|
||||
|
||||
#Nodes
|
||||
|
||||
#node: 1
|
||||
set: integer structural_node_1 = 1; #node label
|
||||
|
||||
#node: 2
|
||||
set: integer structural_node_2 = 2; #node label
|
||||
|
||||
#node: 3
|
||||
set: integer structural_node_3 = 3; #node label
|
||||
|
||||
#node: 4
|
||||
set: integer structural_node_4 = 4; #node label
|
||||
|
||||
#node: 5
|
||||
set: integer structural_node_5 = 5; #node label
|
||||
|
||||
#Joints
|
||||
|
||||
#joint: 1
|
||||
set: integer joint_1 = 1; #joint label
|
||||
|
||||
#joint: 2
|
||||
set: integer joint_2 = 2; #joint label
|
||||
|
||||
#joint: 3
|
||||
set: integer joint_3 = 3; #joint label
|
||||
|
||||
#joint: 4
|
||||
set: integer joint_4 = 4; #joint label
|
||||
|
||||
#joint: 5
|
||||
set: integer joint_5 = 5; #joint label
|
||||
|
||||
#joint: 6
|
||||
set: integer joint_6 = 6; #joint label
|
||||
|
||||
#Nodes: initial conditions
|
||||
|
||||
#node: 1
|
||||
set: real Px_1 = 0.16912189837562464; #X component of the absolute position [m]
|
||||
set: real Py_1 = -0.10055206743263254; #Y component of the absolute position [m]
|
||||
set: real Pz_1 = 0.07867737409397452; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_1 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_1 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_1 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_1 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_1 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_1 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 2
|
||||
set: real Px_2 = 0.018683478687078307; #X component of the absolute position [m]
|
||||
set: real Py_2 = -0.05533171845235879; #Y component of the absolute position [m]
|
||||
set: real Pz_2 = 0.1768528076947657; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_2 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_2 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_2 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_2 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_2 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_2 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 3
|
||||
set: real Px_3 = 0.2890983348369078; #X component of the absolute position [m]
|
||||
set: real Py_3 = -0.06156645049450425; #Y component of the absolute position [m]
|
||||
set: real Pz_3 = 0.09724597715885096; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_3 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_3 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_3 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_3 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_3 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_3 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 4
|
||||
set: real Px_4 = 0.11637356459110539; #X component of the absolute position [m]
|
||||
set: real Py_4 = -0.019655254070140387; #Y component of the absolute position [m]
|
||||
set: real Pz_4 = 0.20651079866339145; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_4 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_4 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_4 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_4 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_4 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_4 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#node: 5
|
||||
set: real Px_5 = 0.15064540729834192; #X component of the absolute position [m]
|
||||
set: real Py_5 = -0.020536937096322302; #Y component of the absolute position [m]
|
||||
set: real Pz_5 = 0.06548008210568429; #Z component of the absolute position [m]
|
||||
|
||||
set: real Vx_5 = 0.0; #X component of the absolute velocity [m/s]
|
||||
set: real Vy_5 = 0.0; #Y component of the absolute velocity [m/s]
|
||||
set: real Vz_5 = 0.0; #Z component of the absolute velocity [m/s]
|
||||
|
||||
set: real Wx_5 = 0.0; #X component of the absolute angular velocity [rad/s]
|
||||
set: real Wy_5 = 0.0; #Y component of the absolute angular velocity [rad/s]
|
||||
set: real Wz_5 = 0.0; #Z component of the absolute angular velocity [rad/s]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Intermediate Variables]
|
||||
|
||||
#Moments of inertia and relative center of mass
|
||||
|
||||
#body 2:
|
||||
set: real Ixx_2 = 6.927961737800001e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_2 = 5.6689424982e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_2 = 2.9053392577e-05; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_2 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_2 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_2 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 4:
|
||||
set: real Ixx_4 = 7.9157004521e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_4 = 7.769349168e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_4 = 3.339121993e-06; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_4 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_4 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_4 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#body 5:
|
||||
set: real Ixx_5 = 7.9157004521e-05; #moment of inertia [kg*m^2]
|
||||
set: real Iyy_5 = 7.769349168e-05; #moment of inertia [kg*m^2]
|
||||
set: real Izz_5 = 3.339121993e-06; #moment of inertia [kg*m^2]
|
||||
|
||||
set: real Rx_5 = 0.0; #X component of the relative center of mass [m]
|
||||
set: real Ry_5 = 0.0; #Y component of the relative center of mass [m]
|
||||
set: real Rz_5 = 0.0; #Z component of the relative center of mass [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Nodes Block]
|
||||
|
||||
begin: nodes;
|
||||
|
||||
structural: structural_node_1,
|
||||
static,
|
||||
Px_1, Py_1, Pz_1, #<absolute_position> [m]
|
||||
3, -0.3539135011019427, 0.9158836712023025, 0.18947911379030236, 2, -0.5084786583487672, -0.018385530501657588, -0.8608782877224926, #<absolute_orientation_matrix>
|
||||
Vx_1, Vy_1, Vz_1, #<absolute_velocity> [m/s]
|
||||
Wx_1, Wy_1, Wz_1; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_2,
|
||||
dynamic,
|
||||
Px_2, Py_2, Pz_2, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_2, Vy_2, Vz_2, #<absolute_velocity> [m/s]
|
||||
Wx_2, Wy_2, Wz_2; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_3,
|
||||
static,
|
||||
Px_3, Py_3, Pz_3, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_3, Vy_3, Vz_3, #<absolute_velocity> [m/s]
|
||||
Wx_3, Wy_3, Wz_3; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_4,
|
||||
dynamic,
|
||||
Px_4, Py_4, Pz_4, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_4, Vy_4, Vz_4, #<absolute_velocity> [m/s]
|
||||
Wx_4, Wy_4, Wz_4; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
structural: structural_node_5,
|
||||
dynamic,
|
||||
Px_5, Py_5, Pz_5, #<absolute_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0, #<absolute_orientation_matrix>
|
||||
Vx_5, Vy_5, Vz_5, #<absolute_velocity> [m/s]
|
||||
Wx_5, Wy_5, Wz_5; #<absolute_angular_velocity> [rad/s]
|
||||
|
||||
end: nodes;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Elements Block]
|
||||
|
||||
begin: elements;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Bodies]
|
||||
|
||||
body: body_2,
|
||||
structural_node_2, #<node_label>
|
||||
mass_2, #<mass> [kg]
|
||||
Rx_2, Ry_2, Rz_2, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_2, Iyy_2, Izz_2, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.35, 0.91, 0.21, 2, 0.78, 0.4, -0.47;
|
||||
|
||||
body: body_4,
|
||||
structural_node_4, #<node_label>
|
||||
mass_4, #<mass> [kg]
|
||||
Rx_4, Ry_4, Rz_4, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_4, Iyy_4, Izz_4, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, 0.78, 0.4, -0.47, 2, -0.36, 0.91, 0.19;
|
||||
|
||||
body: body_5,
|
||||
structural_node_5, #<node_label>
|
||||
mass_5, #<mass> [kg]
|
||||
Rx_5, Ry_5, Rz_5, #<relative_center_of_mass> [m]
|
||||
diag, Ixx_5, Iyy_5, Izz_5, #<inertia matrix> [kg*m^2]
|
||||
orientation, 3, -0.36, 0.91, 0.19, 2, 0.78, 0.4, -0.47;
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Joints]
|
||||
|
||||
joint: joint_1,
|
||||
clamp,
|
||||
structural_node_1, #<node_label>
|
||||
0.16912189837562464, -0.10055206743263254, 0.07867737409397452, #<absolute_pin_position> [m]
|
||||
3, -0.3539135011019427, 0.9158836712023025, 0.18947911379030236, 2, -0.5084786583487672, -0.018385530501657588, -0.8608782877224926; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_2,
|
||||
axial rotation,
|
||||
structural_node_1, #<node_1_label>
|
||||
1.0407603667772492e-11, -0.05247682460581396, -0.00025357557055826873, #<relative_offset_1> [m]
|
||||
orientation, 3, 1.1102230246251565e-16, -1.0, 0.0, 2, guess, #<relative_orientation_matrix_1>
|
||||
structural_node_2, #<node_2_label>
|
||||
0.006998226646402806, -0.00490348349806041, 0.007426083408032554, #<relative_offset_2> [m]
|
||||
orientation, 3, 0.5084786344413901, 0.01838554762064229, 0.8608783014778036, 2, guess, #<relative_orientation_matrix_2>
|
||||
string, "model::drive(1, Time)"; #<angular_velocity> [rad/s]
|
||||
|
||||
joint: joint_3,
|
||||
clamp,
|
||||
structural_node_3, #<node_label>
|
||||
0.2890983348369078, -0.06156645049450425, 0.09724597715885096, #<absolute_pin_position> [m]
|
||||
3, 0.0, 0.0, 1.0, 2, 0.0, 1.0, 0.0; #<absolute_orientation_matrix>
|
||||
|
||||
joint: joint_4,
|
||||
revolute hinge,
|
||||
structural_node_2, #<node_1_label>
|
||||
-0.0011629534118987692, 0.02262071327533141, 0.01746668757489371, #<relative_position_1> [m]
|
||||
orientation, 3, 0.5084786344412178, 0.018385547620640152, 0.8608783014779054, 2, guess, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_4, #<node_2_label>
|
||||
-0.031347177833029705, -0.01617494903756937, 0.018860685712244078, #<relative_position_2> [m]
|
||||
orientation, 3, 0.5084786455601428, 0.018385495401303797, 0.860878296025734, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_5,
|
||||
revolute hinge,
|
||||
structural_node_4, #<node_1_label>
|
||||
0.03388957106083931, 0.016266876514581658, -0.01455629423212079, #<relative_position_1> [m]
|
||||
orientation, 3, 0.50847864556046, 0.0183854954014063, 0.8608782960255446, 2, guess, #<relative_pin_orientation_matrix_1>
|
||||
structural_node_5, #<node_2_label>
|
||||
-0.016813818553224735, 0.036484433510506876, 0.003343892503690739, #<relative_position_2> [m]
|
||||
orientation, 3, 0.5084787180221569, 0.01838550036990011, 0.8608782531198544, 2, guess; #<relative_pin_orientation_matrix_2>
|
||||
|
||||
joint: joint_6,
|
||||
in line,
|
||||
structural_node_3, #<node_1_label>
|
||||
0.0, 0.0, 0.0, #<relative_line_position> [m]
|
||||
3, 0.5094306516594838, 0.018659363391322903, 0.8603093858070039, 2, guess, #<relative_orientation>
|
||||
structural_node_5, #<node_2_label>
|
||||
offset, 0.014271424963118534, -0.03657636101236503, -0.007648283769292526; #<relative_offset> [m]
|
||||
|
||||
#-----------------------------------------------------------------------------
|
||||
# [Drive callers]
|
||||
|
||||
drive caller: 1, name,"drive:1", ramp, 5.0, 0.25, 4.0, 0.0;
|
||||
|
||||
end: elements;
|
||||
|
||||
4005
OndselSolver/MBDynCaseDebug2.mov
Normal file
4005
OndselSolver/MBDynCaseDebug2.mov
Normal file
File diff suppressed because it is too large
Load Diff
78
OndselSolver/MBDynDrive.cpp
Normal file
78
OndselSolver/MBDynDrive.cpp
Normal file
@@ -0,0 +1,78 @@
|
||||
#include <regex>
|
||||
|
||||
#include "MBDynDrive.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
void MbD::MBDynDrive::parseMBDyn(std::string line)
|
||||
{
|
||||
driveString = line;
|
||||
size_t previousPos = 0;
|
||||
auto pos = line.find(":");
|
||||
auto front = line.substr(previousPos, pos - previousPos);
|
||||
assert(front.find("drive caller") != std::string::npos);
|
||||
auto arguments = std::vector<std::string>();
|
||||
std::string argument;
|
||||
while (true) {
|
||||
previousPos = pos;
|
||||
pos = line.find(",", pos + 1);
|
||||
if (pos != std::string::npos) {
|
||||
argument = line.substr(previousPos + 1, pos - previousPos - 1);
|
||||
arguments.push_back(argument);
|
||||
}
|
||||
else {
|
||||
argument = line.substr(previousPos + 1);
|
||||
arguments.push_back(argument);
|
||||
break;
|
||||
}
|
||||
}
|
||||
auto iss = std::istringstream(arguments.at(0));
|
||||
iss >> name;
|
||||
arguments.erase(arguments.begin());
|
||||
assert(arguments.at(0).find("name") != std::string::npos);
|
||||
arguments.erase(arguments.begin());
|
||||
iss = std::istringstream(arguments.at(0));
|
||||
iss >> driveName;
|
||||
driveName = std::regex_replace(driveName, std::regex("\""), "");
|
||||
arguments.erase(arguments.begin());
|
||||
readFunction(arguments);
|
||||
}
|
||||
|
||||
void MbD::MBDynDrive::readFunction(std::vector<std::string>& args)
|
||||
{
|
||||
if (args.empty()) return;
|
||||
std::string str;
|
||||
auto iss = std::istringstream(args.at(0));
|
||||
iss >> str;
|
||||
if (str.find("ramp") != std::string::npos) {
|
||||
args.erase(args.begin());
|
||||
std::string slope, initValue, initTime, finalTime;
|
||||
slope = popOffTop(args);
|
||||
initTime = popOffTop(args);
|
||||
finalTime = popOffTop(args);
|
||||
initValue = popOffTop(args);
|
||||
slope.erase(remove_if(slope.begin(), slope.end(), isspace), slope.end());
|
||||
initTime.erase(remove_if(initTime.begin(), initTime.end(), isspace), initTime.end());
|
||||
finalTime.erase(remove_if(finalTime.begin(), finalTime.end(), isspace), finalTime.end());
|
||||
initValue.erase(remove_if(initValue.begin(), initValue.end(), isspace), initValue.end());
|
||||
|
||||
//f = slope*(time - t0) + f0
|
||||
//rampstep(time, t0, f0, t1, f1)
|
||||
//t0 = initTime
|
||||
//f0 = initValue
|
||||
//t1 = finalTime
|
||||
//f1 = initValue + slope * (finalTime - initTime)
|
||||
auto ss = std::stringstream();
|
||||
ss << "rampstep(time, " << initTime << ", " << initValue << ", " << finalTime << ", "
|
||||
<< initValue << " + " << slope << "*(" << finalTime << " - " << initTime << "))";
|
||||
formula = ss.str();
|
||||
}
|
||||
else {
|
||||
assert(false);
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::MBDynDrive::createASMT()
|
||||
{
|
||||
assert(false);
|
||||
}
|
||||
24
OndselSolver/MBDynDrive.h
Normal file
24
OndselSolver/MBDynDrive.h
Normal file
@@ -0,0 +1,24 @@
|
||||
/***************************************************************************
|
||||
* Copyright (c) 2023 Ondsel, Inc. *
|
||||
* *
|
||||
* This file is part of OndselSolver. *
|
||||
* *
|
||||
* See LICENSE file for details about copyright. *
|
||||
***************************************************************************/
|
||||
|
||||
#pragma once
|
||||
#include "MBDynElement.h"
|
||||
|
||||
namespace MbD {
|
||||
class MBDynDrive : public MBDynElement
|
||||
{
|
||||
public:
|
||||
void parseMBDyn(std::string line);
|
||||
void readFunction(std::vector<std::string>& args);
|
||||
void createASMT() override;
|
||||
|
||||
std::string driveString, driveName, formula;
|
||||
|
||||
};
|
||||
}
|
||||
|
||||
@@ -32,6 +32,55 @@ void MbD::MBDynItem::parseMBDyn(std::vector<std::string>& lines)
|
||||
assert(false);
|
||||
}
|
||||
|
||||
std::vector<std::string> MbD::MBDynItem::collectArgumentsFor(std::string title, std::string& statement)
|
||||
{
|
||||
size_t previousPos = 0;
|
||||
auto pos = statement.find(":");
|
||||
auto front = statement.substr(previousPos, pos - previousPos);
|
||||
assert(front.find(title) != std::string::npos);
|
||||
auto arguments = std::vector<std::string>();
|
||||
std::string argument;
|
||||
while (true) {
|
||||
previousPos = pos;
|
||||
pos = statement.find(",", pos + 1);
|
||||
if (pos != std::string::npos) {
|
||||
argument = statement.substr(previousPos + 1, pos - previousPos - 1);
|
||||
arguments.push_back(argument);
|
||||
}
|
||||
else {
|
||||
argument = statement.substr(previousPos + 1);
|
||||
arguments.push_back(argument);
|
||||
break;
|
||||
}
|
||||
}
|
||||
auto arguments2 = std::vector<std::string>();
|
||||
while (!arguments.empty()) {
|
||||
argument = arguments[0];
|
||||
auto n = std::count(argument.begin(), argument.end(), '"');
|
||||
if ((n % 2) == 0) {
|
||||
arguments2.push_back(argument);
|
||||
arguments.erase(arguments.begin());
|
||||
}
|
||||
else {
|
||||
//Need to find matching '"'
|
||||
auto it = std::find_if(arguments.begin() + 1, arguments.end(), [](const std::string& s) {
|
||||
auto nn = std::count(s.begin(), s.end(), '"');
|
||||
if ((nn % 2) == 1) return true;
|
||||
});
|
||||
std::vector<std::string> needToCombineArgs(arguments.begin(), it + 1);
|
||||
arguments.erase(arguments.begin(), it + 1);
|
||||
std::stringstream ss;
|
||||
ss << needToCombineArgs[0];
|
||||
needToCombineArgs.erase(needToCombineArgs.begin());
|
||||
for (auto& arg : needToCombineArgs) {
|
||||
ss << ',' << arg;
|
||||
}
|
||||
arguments2.push_back(ss.str());
|
||||
}
|
||||
}
|
||||
return arguments2;
|
||||
}
|
||||
|
||||
std::vector<std::string>::iterator MbD::MBDynItem::findLineWith(std::vector<std::string>& lines, std::vector<std::string>& tokens)
|
||||
{
|
||||
auto it = std::find_if(lines.begin(), lines.end(), [&](const std::string& line) {
|
||||
@@ -56,6 +105,21 @@ std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> MbD::MBDynItem::mbdynNo
|
||||
return owner->mbdynNodes();
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynBody>>> MbD::MBDynItem::mbdynBodies()
|
||||
{
|
||||
return owner->mbdynBodies();
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynJoint>>> MbD::MBDynItem::mbdynJoints()
|
||||
{
|
||||
return owner->mbdynJoints();
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynDrive>>> MbD::MBDynItem::mbdynDrives()
|
||||
{
|
||||
return owner->mbdynDrives();
|
||||
}
|
||||
|
||||
std::vector<std::string> MbD::MBDynItem::nodeNames()
|
||||
{
|
||||
return owner->nodeNames();
|
||||
@@ -96,6 +160,18 @@ std::shared_ptr<ASMTAssembly> MbD::MBDynItem::asmtAssembly()
|
||||
return owner->asmtAssembly();
|
||||
}
|
||||
|
||||
std::string MbD::MBDynItem::formulaFromDrive(std::string driveName, std::string varName)
|
||||
{
|
||||
std::vector<std::string> tokens{ "drive:", driveName };
|
||||
auto drives = mbdynDrives();
|
||||
auto it = std::find_if(drives->begin(), drives->end(), [&](auto& drive) {
|
||||
return lineHasTokens(drive->driveName, tokens);
|
||||
});
|
||||
auto formula = (*it)->formula;
|
||||
assert(varName == "Time");
|
||||
return formula;
|
||||
}
|
||||
|
||||
FColDsptr MbD::MBDynItem::readVector3(std::vector<std::string>& args)
|
||||
{
|
||||
auto parser = std::make_shared<SymbolicParser>();
|
||||
@@ -336,3 +412,11 @@ std::string MbD::MBDynItem::readStringOffTop(std::vector<std::string>& args)
|
||||
iss >> str;
|
||||
return str;
|
||||
}
|
||||
|
||||
std::string MbD::MBDynItem::readToken(std::string& line)
|
||||
{
|
||||
auto iss = std::istringstream(line);
|
||||
std::string str;
|
||||
iss >> str;
|
||||
return str;
|
||||
}
|
||||
|
||||
@@ -16,6 +16,8 @@ namespace MbD {
|
||||
class MBDynNode;
|
||||
class ASMTItem;
|
||||
class MBDynBody;
|
||||
class MBDynJoint;
|
||||
class MBDynDrive;
|
||||
class ASMTAssembly;
|
||||
|
||||
class MBDynItem
|
||||
@@ -28,9 +30,13 @@ namespace MbD {
|
||||
void noop();
|
||||
//void setName(std::string str);
|
||||
virtual void parseMBDyn(std::vector<std::string>& lines);
|
||||
static std::vector<std::string> collectArgumentsFor(std::string title, std::string& statement);
|
||||
std::vector<std::string>::iterator findLineWith(std::vector<std::string>& lines, std::vector<std::string>& tokens);
|
||||
bool lineHasTokens(const std::string& line, std::vector<std::string>& tokens);
|
||||
virtual std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> mbdynNodes();
|
||||
virtual std::shared_ptr<std::vector<std::shared_ptr<MBDynBody>>> mbdynBodies();
|
||||
virtual std::shared_ptr<std::vector<std::shared_ptr<MBDynJoint>>> mbdynJoints();
|
||||
virtual std::shared_ptr<std::vector<std::shared_ptr<MBDynDrive>>> mbdynDrives();
|
||||
virtual std::vector<std::string> nodeNames();
|
||||
virtual std::shared_ptr<std::map<std::string, Symsptr>> mbdynVariables();
|
||||
virtual std::shared_ptr<std::map<std::string, std::shared_ptr<MBDynReference>>> mbdynReferences();
|
||||
@@ -39,6 +45,7 @@ namespace MbD {
|
||||
virtual int nodeidAt(std::string nodeName);
|
||||
virtual std::shared_ptr<MBDynBody> bodyWithNode(std::string nodeName);
|
||||
virtual std::shared_ptr<ASMTAssembly> asmtAssembly();
|
||||
virtual std::string formulaFromDrive(std::string driveName, std::string varName);
|
||||
|
||||
FColDsptr readVector3(std::vector<std::string>& args);
|
||||
FColDsptr readPosition(std::vector<std::string>& args);
|
||||
@@ -47,6 +54,7 @@ namespace MbD {
|
||||
FMatDsptr readBasicOrientation(std::vector<std::string>& args);
|
||||
std::string popOffTop(std::vector<std::string>& args);
|
||||
std::string readStringOffTop(std::vector<std::string>& args);
|
||||
std::string readToken(std::string& line);
|
||||
|
||||
std::string name;
|
||||
MBDynItem* owner;
|
||||
|
||||
@@ -20,25 +20,26 @@ void MbD::MBDynJoint::initialize()
|
||||
void MbD::MBDynJoint::parseMBDyn(std::string line)
|
||||
{
|
||||
jointString = line;
|
||||
size_t previousPos = 0;
|
||||
auto pos = line.find(":");
|
||||
auto front = line.substr(previousPos, pos - previousPos);
|
||||
assert(front.find("joint") != std::string::npos);
|
||||
auto arguments = std::vector<std::string>();
|
||||
std::string argument;
|
||||
while (true) {
|
||||
previousPos = pos;
|
||||
pos = line.find(",", pos + 1);
|
||||
if (pos != std::string::npos) {
|
||||
argument = line.substr(previousPos + 1, pos - previousPos - 1);
|
||||
arguments.push_back(argument);
|
||||
}
|
||||
else {
|
||||
argument = line.substr(previousPos + 1);
|
||||
arguments.push_back(argument);
|
||||
break;
|
||||
}
|
||||
}
|
||||
auto arguments = collectArgumentsFor("joint", line);
|
||||
//size_t previousPos = 0;
|
||||
//auto pos = line.find(":");
|
||||
//auto front = line.substr(previousPos, pos - previousPos);
|
||||
//assert(front.find("joint") != std::string::npos);
|
||||
//auto arguments = std::vector<std::string>();
|
||||
//std::string argument;
|
||||
//while (true) {
|
||||
// previousPos = pos;
|
||||
// pos = line.find(",", pos + 1);
|
||||
// if (pos != std::string::npos) {
|
||||
// argument = line.substr(previousPos + 1, pos - previousPos - 1);
|
||||
// arguments.push_back(argument);
|
||||
// }
|
||||
// else {
|
||||
// argument = line.substr(previousPos + 1);
|
||||
// arguments.push_back(argument);
|
||||
// break;
|
||||
// }
|
||||
//}
|
||||
auto ss = std::stringstream();
|
||||
auto iss = std::istringstream(arguments.at(0));
|
||||
iss >> name;
|
||||
@@ -119,7 +120,7 @@ void MbD::MBDynJoint::parseMBDyn(std::string line)
|
||||
mkr1->nodeStr = "Assembly";
|
||||
mkr1->rPmP = std::make_shared<FullColumn<double>>(3);
|
||||
mkr1->aAPm = FullMatrixDouble::identitysptr(3);
|
||||
readMarkerJ(arguments);
|
||||
readClampMarkerJ(arguments);
|
||||
return;
|
||||
}
|
||||
else if (joint_type == "prismatic") {
|
||||
@@ -160,6 +161,15 @@ void MbD::MBDynJoint::readMarkerJ(std::vector<std::string>& args)
|
||||
mkr2->parseMBDyn(args);
|
||||
}
|
||||
|
||||
void MbD::MBDynJoint::readClampMarkerJ(std::vector<std::string>& args)
|
||||
{
|
||||
if (args.empty()) return;
|
||||
mkr2 = std::make_shared<MBDynMarker>();
|
||||
mkr2->owner = this;
|
||||
mkr2->nodeStr = readStringOffTop(args);
|
||||
mkr2->parseMBDynClamp(args);
|
||||
}
|
||||
|
||||
void MbD::MBDynJoint::readFunction(std::vector<std::string>& args)
|
||||
{
|
||||
if (args.empty()) return;
|
||||
@@ -177,7 +187,8 @@ void MbD::MBDynJoint::readFunction(std::vector<std::string>& args)
|
||||
auto ss = std::stringstream();
|
||||
ss << slope << "*(time - " << initTime << ") + " << initValue;
|
||||
formula = ss.str();
|
||||
} else if (str.find("single") != std::string::npos) {
|
||||
}
|
||||
else if (str.find("single") != std::string::npos) {
|
||||
args.erase(args.begin());
|
||||
auto vec3 = readVector3(args);
|
||||
assert(vec3->at(0) == 0 && vec3->at(1) == 0 && vec3->at(2) == 1);
|
||||
@@ -185,6 +196,11 @@ void MbD::MBDynJoint::readFunction(std::vector<std::string>& args)
|
||||
formula = popOffTop(args);
|
||||
formula = std::regex_replace(formula, std::regex("\""), "");
|
||||
}
|
||||
else if (str.find("string") != std::string::npos) {
|
||||
args.erase(args.begin());
|
||||
formula = popOffTop(args);
|
||||
formula = std::regex_replace(formula, std::regex("\""), "");
|
||||
}
|
||||
else {
|
||||
assert(false);
|
||||
}
|
||||
@@ -216,7 +232,7 @@ void MbD::MBDynJoint::createASMT()
|
||||
asmtItem = asmtMotion;
|
||||
asmtMotion->setName(name.append("Motion"));
|
||||
asmtMotion->setMotionJoint(asmtJoint->fullName(""));
|
||||
asmtMotion->setRotationZ(formula);
|
||||
asmtMotion->setRotationZ(asmtFormulaIntegral());
|
||||
asmtAsm->addMotion(asmtMotion);
|
||||
return;
|
||||
}
|
||||
@@ -252,3 +268,37 @@ void MbD::MBDynJoint::createASMT()
|
||||
asmtJoint->setMarkerJ(mkr2->asmtItem->fullName(""));
|
||||
asmtAssembly()->addJoint(asmtJoint);
|
||||
}
|
||||
|
||||
std::string MbD::MBDynJoint::asmtFormula()
|
||||
{
|
||||
auto ss = std::stringstream();
|
||||
std::string drivestr = "model::drive";
|
||||
size_t previousPos = 0;
|
||||
auto pos = formula.find(drivestr);
|
||||
ss << formula.substr(previousPos, pos - previousPos);
|
||||
while (pos != std::string::npos) {
|
||||
previousPos = pos;
|
||||
pos = formula.find('(', pos + 1);
|
||||
previousPos = pos;
|
||||
pos = formula.find(',', pos + 1);
|
||||
auto driveName = formula.substr(previousPos + 1, pos - previousPos - 1);
|
||||
driveName = readToken(driveName);
|
||||
previousPos = pos;
|
||||
pos = formula.find(')', pos + 1);
|
||||
auto varName = formula.substr(previousPos + 1, pos - previousPos - 1);
|
||||
varName = readToken(varName);
|
||||
//Insert drive formula
|
||||
ss << formulaFromDrive(driveName, varName);
|
||||
previousPos = pos;
|
||||
pos = formula.find(drivestr, pos + 1);
|
||||
ss << formula.substr(previousPos + 1, pos - previousPos);
|
||||
}
|
||||
return ss.str();
|
||||
}
|
||||
|
||||
std::string MbD::MBDynJoint::asmtFormulaIntegral()
|
||||
{
|
||||
auto ss = std::stringstream();
|
||||
ss << "integral(time, " << asmtFormula() << ")";
|
||||
return ss.str();
|
||||
}
|
||||
|
||||
@@ -18,8 +18,11 @@ namespace MbD {
|
||||
void parseMBDyn(std::string line);
|
||||
void readMarkerI(std::vector<std::string>& args);
|
||||
void readMarkerJ(std::vector<std::string>& args);
|
||||
void readClampMarkerJ(std::vector<std::string>& args);
|
||||
void readFunction(std::vector<std::string>& args);
|
||||
void createASMT() override;
|
||||
std::string asmtFormula();
|
||||
std::string asmtFormulaIntegral();
|
||||
|
||||
std::string jointString, joint_type, node_1_label, node_2_label;
|
||||
std::shared_ptr<MBDynMarker> mkr1, mkr2;
|
||||
|
||||
@@ -32,6 +32,18 @@ void MbD::MBDynMarker::parseMBDyn(std::vector<std::string>& args)
|
||||
}
|
||||
}
|
||||
|
||||
void MbD::MBDynMarker::parseMBDynClamp(std::vector<std::string>& args)
|
||||
{
|
||||
//rOmO = rOPO + aAOP*rPmP
|
||||
//aAOm = aAOP * aAPm
|
||||
auto rOmO = std::make_shared<FullColumn<double>>(3);
|
||||
auto aAOm = FullMatrixDouble::identitysptr(3);
|
||||
auto rOPO = readPosition(args);
|
||||
auto aAOP = readOrientation(args);
|
||||
rPmP = aAOP->transposeTimesFullColumn(rOmO->minusFullColumn(rOPO));
|
||||
aAPm = aAOP->transposeTimesFullMatrix(aAOm);
|
||||
}
|
||||
|
||||
void MbD::MBDynMarker::createASMT()
|
||||
{
|
||||
auto asmtAsm = asmtAssembly();
|
||||
|
||||
@@ -14,7 +14,8 @@ namespace MbD {
|
||||
class MBDynMarker : public MBDynItem
|
||||
{
|
||||
public:
|
||||
void parseMBDyn(std::vector<std::string>& args) override;
|
||||
void parseMBDyn(std::vector<std::string>& args);
|
||||
void parseMBDynClamp(std::vector<std::string>& args);
|
||||
void createASMT() override;
|
||||
|
||||
std::string nodeStr;
|
||||
|
||||
@@ -20,13 +20,7 @@ void MbD::MBDynNode::outputLine(int i, std::ostream& os)
|
||||
auto x = asmtPart->xs->at(i);
|
||||
auto y = asmtPart->ys->at(i);
|
||||
auto z = asmtPart->zs->at(i);
|
||||
auto bryantAngles = std::make_shared<EulerAngles<double>>();
|
||||
bryantAngles->setRotOrder(1, 2, 3);
|
||||
bryantAngles->at(0) = asmtPart->bryxs->at(i);
|
||||
bryantAngles->at(1) = asmtPart->bryys->at(i);
|
||||
bryantAngles->at(2) = asmtPart->bryzs->at(i);
|
||||
bryantAngles->calc();
|
||||
auto aA = bryantAngles->aA;
|
||||
auto aA = asmtPart->getRotationMatrix(i);
|
||||
auto vx = asmtPart->vxs->at(i);
|
||||
auto vy = asmtPart->vys->at(i);
|
||||
auto vz = asmtPart->vzs->at(i);
|
||||
|
||||
@@ -3,6 +3,7 @@
|
||||
#include <fstream>
|
||||
#include <algorithm>
|
||||
#include <numeric>
|
||||
#include <iomanip>
|
||||
|
||||
#include "MBDynSystem.h"
|
||||
#include "CREATE.h"
|
||||
@@ -14,12 +15,12 @@
|
||||
#include "ASMTConstantGravity.h"
|
||||
#include "ASMTTime.h"
|
||||
#include "MBDynBody.h"
|
||||
#include "MBDynJoint.h"
|
||||
#include "MBDynStructural.h"
|
||||
#include "SymbolicParser.h"
|
||||
#include "BasicUserFunction.h"
|
||||
#include "MBDynJoint.h"
|
||||
#include "MBDynReference.h"
|
||||
#include <iomanip>
|
||||
#include "MBDynDrive.h"
|
||||
|
||||
using namespace MbD;
|
||||
|
||||
@@ -38,7 +39,6 @@ void MbD::MBDynSystem::runFile(const char* filename)
|
||||
system->setFilename(filename);
|
||||
system->parseMBDyn(statements);
|
||||
system->runKINEMATIC();
|
||||
system->outputFiles();
|
||||
}
|
||||
|
||||
void MbD::MBDynSystem::parseMBDyn(std::vector<std::string>& lines)
|
||||
@@ -51,7 +51,7 @@ void MbD::MBDynSystem::parseMBDyn(std::vector<std::string>& lines)
|
||||
readReferences(lines);
|
||||
readNodesBlock(lines);
|
||||
readElementsBlock(lines);
|
||||
|
||||
assert(lines.empty());
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> MbD::MBDynSystem::mbdynNodes()
|
||||
@@ -59,6 +59,21 @@ std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> MbD::MBDynSystem::mbdyn
|
||||
return nodes;
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynBody>>> MbD::MBDynSystem::mbdynBodies()
|
||||
{
|
||||
return bodies;
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynJoint>>> MbD::MBDynSystem::mbdynJoints()
|
||||
{
|
||||
return joints;
|
||||
}
|
||||
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynDrive>>> MbD::MBDynSystem::mbdynDrives()
|
||||
{
|
||||
return drives;
|
||||
}
|
||||
|
||||
std::shared_ptr<std::map<std::string, Symsptr>> MbD::MBDynSystem::mbdynVariables()
|
||||
{
|
||||
return variables;
|
||||
@@ -77,7 +92,8 @@ void MbD::MBDynSystem::createASMT()
|
||||
asmtItem->setName("Assembly");
|
||||
initialValue->createASMT();
|
||||
for (auto& node : *nodes) node->createASMT();
|
||||
for (auto& element : *elements) element->createASMT();
|
||||
for (auto& body : *bodies) body->createASMT();
|
||||
for (auto& joint : *joints) joint->createASMT();
|
||||
}
|
||||
|
||||
std::shared_ptr<MBDynNode> MbD::MBDynSystem::nodeAt(std::string nodeName)
|
||||
@@ -95,12 +111,8 @@ int MbD::MBDynSystem::nodeidAt(std::string nodeName)
|
||||
|
||||
std::shared_ptr<MBDynBody> MbD::MBDynSystem::bodyWithNode(std::string nodeName)
|
||||
{
|
||||
for (auto& element : *elements) {
|
||||
std::string str = typeid(element).name();
|
||||
if (str.find("MBDynBody") != std::string::npos) {
|
||||
auto body = std::static_pointer_cast<MBDynBody>(element);
|
||||
if (body->nodeName == nodeName) return body;
|
||||
}
|
||||
for (auto& body : *bodies) {
|
||||
if (body->nodeName == nodeName) return body;
|
||||
}
|
||||
return nullptr;
|
||||
}
|
||||
@@ -122,8 +134,11 @@ std::vector<std::string> MbD::MBDynSystem::nodeNames()
|
||||
void MbD::MBDynSystem::runKINEMATIC()
|
||||
{
|
||||
createASMT();
|
||||
asmtAssembly()->outputFile("assembly.asmt");
|
||||
std::static_pointer_cast<ASMTAssembly>(asmtItem)->runKINEMATIC();
|
||||
outputFiles();
|
||||
asmtAssembly()->outputFile("assembly2.asmt");
|
||||
asmtAssembly()->outputFile("smalltalk.asmt");
|
||||
}
|
||||
|
||||
void MbD::MBDynSystem::outputFiles()
|
||||
@@ -302,31 +317,47 @@ void MbD::MBDynSystem::parseMBDynNodes(std::vector<std::string>& lines)
|
||||
|
||||
void MbD::MBDynSystem::parseMBDynElements(std::vector<std::string>& lines)
|
||||
{
|
||||
elements = std::make_shared<std::vector<std::shared_ptr<MBDynElement>>>();
|
||||
std::vector<std::string> bodyToken{ "body:" };
|
||||
std::vector<std::string> jointToken{ "joint:" };
|
||||
assert(lines[0].find("begin: elements") != std::string::npos);
|
||||
lines.erase(lines.begin());
|
||||
bodies = std::make_shared<std::vector<std::shared_ptr<MBDynBody>>>();
|
||||
joints = std::make_shared<std::vector<std::shared_ptr<MBDynJoint>>>();
|
||||
drives = std::make_shared<std::vector<std::shared_ptr<MBDynDrive>>>();
|
||||
std::vector<std::string> bodyTokens{ "body:" };
|
||||
std::vector<std::string> jointTokens{ "joint:" };
|
||||
std::vector<std::string> driveTokens{ "drive", "caller:" };
|
||||
std::vector<std::string>::iterator it;
|
||||
while (true) {
|
||||
it = findLineWith(lines, bodyToken);
|
||||
it = findLineWith(lines, bodyTokens);
|
||||
if (it != lines.end()) {
|
||||
auto body = std::make_shared<MBDynBody>();
|
||||
body->owner = this;
|
||||
body->parseMBDyn(*it);
|
||||
elements->push_back(body);
|
||||
bodies->push_back(body);
|
||||
lines.erase(it);
|
||||
continue;
|
||||
}
|
||||
it = findLineWith(lines, jointToken);
|
||||
it = findLineWith(lines, jointTokens);
|
||||
if (it != lines.end()) {
|
||||
auto joint = std::make_shared<MBDynJoint>();
|
||||
joint->owner = this;
|
||||
joint->parseMBDyn(*it);
|
||||
elements->push_back(joint);
|
||||
joints->push_back(joint);
|
||||
lines.erase(it);
|
||||
continue;
|
||||
}
|
||||
it = findLineWith(lines, driveTokens);
|
||||
if (it != lines.end()) {
|
||||
auto drive = std::make_shared<MBDynDrive>();
|
||||
drive->owner = this;
|
||||
drive->parseMBDyn(*it);
|
||||
drives->push_back(drive);
|
||||
lines.erase(it);
|
||||
continue;
|
||||
}
|
||||
break;
|
||||
}
|
||||
assert(lines[0].find("end: elements") != std::string::npos);
|
||||
lines.erase(lines.begin());
|
||||
}
|
||||
|
||||
void MbD::MBDynSystem::parseMBDynVariables(std::vector<std::string>& lines)
|
||||
@@ -349,6 +380,7 @@ void MbD::MBDynSystem::parseMBDynVariables(std::vector<std::string>& lines)
|
||||
auto userFunc = std::make_shared<BasicUserFunction>(str, 1.0);
|
||||
parser->parseUserFunction(userFunc);
|
||||
auto sym = parser->stack->top();
|
||||
auto val = sym->getValue();
|
||||
variables->insert(std::make_pair(variable, sym));
|
||||
lines.erase(it);
|
||||
}
|
||||
|
||||
@@ -11,6 +11,7 @@
|
||||
#include <string>
|
||||
|
||||
#include "MBDynItem.h"
|
||||
#include "MBDynDrive.h"
|
||||
|
||||
namespace MbD {
|
||||
class MBDynData;
|
||||
@@ -37,6 +38,9 @@ namespace MbD {
|
||||
void parseMBDynLabels(std::vector<std::string>& lines);
|
||||
void parseMBDynReferences(std::vector<std::string>& lines);
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> mbdynNodes() override;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynBody>>> mbdynBodies() override;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynJoint>>> mbdynJoints() override;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynDrive>>> mbdynDrives() override;
|
||||
std::shared_ptr<std::map<std::string, Symsptr>> mbdynVariables() override;
|
||||
std::shared_ptr<std::map<std::string, std::shared_ptr<MBDynReference>>> mbdynReferences() override;
|
||||
void createASMT() override;
|
||||
@@ -63,7 +67,9 @@ namespace MbD {
|
||||
std::shared_ptr<MBDynInitialValue> initialValue;
|
||||
std::shared_ptr<MBDynControlData> controlData;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynNode>>> nodes;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynElement>>> elements;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynBody>>> bodies;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynJoint>>> joints;
|
||||
std::shared_ptr<std::vector<std::shared_ptr<MBDynDrive>>> drives;
|
||||
std::shared_ptr<std::map<std::string, Symsptr>> variables;
|
||||
std::shared_ptr<std::map<std::string, int>> labels;
|
||||
std::shared_ptr<std::map<std::string, std::shared_ptr<MBDynReference>>> references;
|
||||
|
||||
@@ -61,7 +61,7 @@ void MarkerFrame::initializeGlobally()
|
||||
|
||||
void MarkerFrame::postInput()
|
||||
{
|
||||
Item::postInput();
|
||||
CartesianFrame::postInput();
|
||||
endFramesDo([](EndFrmsptr endFrame) { endFrame->postInput(); });
|
||||
}
|
||||
|
||||
@@ -82,7 +82,7 @@ void MarkerFrame::calcPostDynCorrectorIteration()
|
||||
|
||||
void MarkerFrame::prePosIC()
|
||||
{
|
||||
Item::prePosIC();
|
||||
CartesianFrame::prePosIC();
|
||||
endFramesDo([](EndFrmsptr endFrame) { endFrame->prePosIC(); });
|
||||
}
|
||||
|
||||
@@ -153,7 +153,7 @@ void MarkerFrame::setqsudotlam(FColDsptr col)
|
||||
|
||||
void MarkerFrame::postPosICIteration()
|
||||
{
|
||||
Item::postPosICIteration();
|
||||
CartesianFrame::postPosICIteration();
|
||||
endFramesDo([](EndFrmsptr endFrame) { endFrame->postPosICIteration(); });
|
||||
}
|
||||
|
||||
@@ -174,7 +174,7 @@ void MarkerFrame::storeDynState()
|
||||
|
||||
void MarkerFrame::preVelIC()
|
||||
{
|
||||
Item::preVelIC();
|
||||
CartesianFrame::preVelIC();
|
||||
endFramesDo([](EndFrmsptr endFrame) { endFrame->preVelIC(); });
|
||||
}
|
||||
|
||||
@@ -185,7 +185,7 @@ void MarkerFrame::postVelIC()
|
||||
|
||||
void MarkerFrame::preAccIC()
|
||||
{
|
||||
Item::preAccIC();
|
||||
CartesianFrame::preAccIC();
|
||||
endFramesDo([](EndFrmsptr endFrame) { endFrame->preAccIC(); });
|
||||
}
|
||||
|
||||
|
||||
@@ -38,9 +38,7 @@ namespace MbD {
|
||||
void addEndFrame(EndFrmsptr x);
|
||||
void initializeLocally() override;
|
||||
void initializeGlobally() override;
|
||||
void postInput() override;
|
||||
void calcPostDynCorrectorIteration() override;
|
||||
void prePosIC() override;
|
||||
int iqX();
|
||||
int iqE();
|
||||
void endFramesDo(const std::function <void(EndFrmsptr)>& f);
|
||||
@@ -55,12 +53,14 @@ namespace MbD {
|
||||
void setqsudot(FColDsptr col) override;
|
||||
void setqsudotlam(FColDsptr col) override;
|
||||
void setqsuddotlam(FColDsptr col) override;
|
||||
void storeDynState() override;
|
||||
void postInput() override;
|
||||
void postPosICIteration() override;
|
||||
void postVelIC() override;
|
||||
void postPosIC() override;
|
||||
void preDyn() override;
|
||||
void storeDynState() override;
|
||||
void prePosIC() override;
|
||||
void preVelIC() override;
|
||||
void postVelIC() override;
|
||||
void preAccIC() override;
|
||||
FColDsptr qXdot();
|
||||
std::shared_ptr<EulerParametersDot<double>> qEdot();
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user