diff --git a/VirtualRobot/CMakeLists.txt b/VirtualRobot/CMakeLists.txt
index f09afe8aab09f035f22154b49bfd182bd360abe8..85be63ded9ab3fc6ac1e8c303c036952ee23c9c0 100644
--- a/VirtualRobot/CMakeLists.txt
+++ b/VirtualRobot/CMakeLists.txt
@@ -326,6 +326,8 @@ SET(SOURCES
     Nodes/RobotNodeActuator.cpp
     Nodes/RobotNodeHemisphere.cpp
     Nodes/RobotNodeHemisphereFactory.cpp
+    Nodes/RobotNodeFourBar.cpp
+    Nodes/RobotNodeFourBarFactory.cpp
     Nodes/RobotNodeFixed.cpp
     Nodes/RobotNodeFixedFactory.cpp
     Nodes/RobotNodePrismatic.cpp
@@ -335,6 +337,8 @@ SET(SOURCES
     Nodes/Sensor.cpp
     Nodes/HemisphereJoint/Expressions.cpp
     Nodes/HemisphereJoint/Joint.cpp
+    Nodes/FourBar/Expressions.cpp
+    Nodes/FourBar/Joint.cpp
 
     TimeOptimalTrajectory/Path.cpp
     TimeOptimalTrajectory/TimeOptimalTrajectory.cpp
@@ -568,6 +572,8 @@ SET(INCLUDES
     Nodes/RobotNodeActuator.h
     Nodes/RobotNodeHemisphere.h
     Nodes/RobotNodeHemisphereFactory.h
+    Nodes/RobotNodeFourBar.h
+    Nodes/RobotNodeFourBarFactory.h
     Nodes/RobotNodeFactory.h
     Nodes/RobotNodeFixed.h
     Nodes/RobotNodeFixedFactory.h
@@ -579,6 +585,8 @@ SET(INCLUDES
     Nodes/SensorFactory.h
     Nodes/HemisphereJoint/Expressions.h
     Nodes/HemisphereJoint/Joint.h
+    Nodes/FourBar/Expressions.h
+    Nodes/FourBar/Joint.h
 
     TimeOptimalTrajectory/Path.h
     TimeOptimalTrajectory/TimeOptimalTrajectory.h
diff --git a/VirtualRobot/IK/DifferentialIK.cpp b/VirtualRobot/IK/DifferentialIK.cpp
index fab7724348723ef73a01ddb24f3fd06d2f965bbc..e3a0a1ef355edee8d5c48e1213d6170576533c1f 100644
--- a/VirtualRobot/IK/DifferentialIK.cpp
+++ b/VirtualRobot/IK/DifferentialIK.cpp
@@ -7,6 +7,8 @@
 #include "../VirtualRobotException.h"
 #include "../CollisionDetection/CollisionChecker.h"
 #include <VirtualRobot/Nodes/RobotNodeHemisphere.h>
+#include <VirtualRobot/Nodes/RobotNodeFourBar.h>
+#include <VirtualRobot/Nodes/RobotNodeHemisphere.h>
 
 #include <Eigen/Geometry>
 
@@ -507,6 +509,11 @@ namespace VirtualRobot
                         // Pass
                     }
                 }
+                else if (dof->isFourBarJoint())
+                {
+                    const RobotNodeFourBar* fourBarJoint = dynamic_cast<RobotNodeFourBar*>(dof.get());
+                    // FIXME implement
+                }
             }
 
 #ifdef CHECK_PERFORMANCE
diff --git a/VirtualRobot/Nodes/FourBar/Expressions.cpp b/VirtualRobot/Nodes/FourBar/Expressions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..41d3b81de1244d033cffb63bad43d836e94a579b
--- /dev/null
+++ b/VirtualRobot/Nodes/FourBar/Expressions.cpp
@@ -0,0 +1,245 @@
+/*
+ * This file was generated automatically on 2022-06-09 10:41.
+ */
+
+#include "Expressions.h"
+
+#include <cmath>
+
+
+namespace VirtualRobot::four_bar
+{
+
+void Expressions::compute(double a1, double a2, double lever, double theta0)
+{
+    this->a1 = a1;
+    this->a2 = a2;
+    this->lever = lever;
+    this->theta0 = theta0;
+
+    _lever_p_2 = (lever * lever);
+    _a2_p_2 = (a2 * a2);
+    __s_a2_p_2 = (-1 * _a2_p_2);
+    __s_a2_p_2_a_lever_p_2 = (_lever_p_2 + __s_a2_p_2);
+    _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ = std::pow(__s_a2_p_2_a_lever_p_2, -0.5);
+    _lever_p_4 = std::pow(lever, 4);
+    _a1_p_2 = (a1 * a1);
+    __s_a1_p_2_m_a2_p_2 = (-1 * _a1_p_2 * _a2_p_2);
+    __s_a1_p_2_m_a2_p_2_a_lever_p_4 = (_lever_p_4 + __s_a1_p_2_m_a2_p_2);
+    _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ = (1 / __s_a1_p_2_m_a2_p_2_a_lever_p_4);
+    _lever_p_5 = std::pow(lever, 5);
+    _sin_l_theta0_r_ = std::sin(theta0);
+    _lever_p_5_m_sin_l_theta0_r_ = (_lever_p_5 * _sin_l_theta0_r_);
+    _lever_p_8 = std::pow(lever, 8);
+    _lever_p_6 = std::pow(lever, 6);
+    __s_a1_p_2_m_lever_p_6 = (-1 * _a1_p_2 * _lever_p_6);
+    _a1_p_4 = std::pow(a1, 4);
+    _a2_p_4 = std::pow(a2, 4);
+    __s_a1_p_4_m_a2_p_4 = (-1 * _a1_p_4 * _a2_p_4);
+    __s_a2_p_2_m_lever_p_6 = (-1 * _a2_p_2 * _lever_p_6);
+    _sin_l_theta0_r__p_2 = (_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    __s_2_m_lever_p_8_m_sin_l_theta0_r__p_2 = (-2 * _lever_p_8 * _sin_l_theta0_r__p_2);
+    _a1_p_2_m_a2_p_4_m_lever_p_2 = (_a1_p_2 * _a2_p_4 * _lever_p_2);
+    _a1_p_4_m_a2_p_2_m_lever_p_2 = (_a1_p_4 * _a2_p_2 * _lever_p_2);
+    _2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (2 * _a1_p_2 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (2 * _a2_p_2 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _a2_p_3 = std::pow(a2, 3);
+    __s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-2 * a1 * _a2_p_3 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _a1_p_3 = std::pow(a1, 3);
+    __s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-2 * a2 * _a1_p_3 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    __s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-2 * _a1_p_2 * _a2_p_2 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (2 * a1 * a2 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2 = (2 * _a1_p_3 * _a2_p_3 * _lever_p_2 * _sin_l_theta0_r__p_2);
+    __s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8 = (_lever_p_8 + __s_a1_p_2_m_lever_p_6 + __s_a1_p_4_m_a2_p_4 + __s_a2_p_2_m_lever_p_6 + __s_2_m_lever_p_8_m_sin_l_theta0_r__p_2 + _a1_p_2_m_a2_p_4_m_lever_p_2 + _a1_p_4_m_a2_p_2_m_lever_p_2 + _2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 + _2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 + __s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 + __s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 + __s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 + _2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 + _2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2);
+    _sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = std::pow(__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8, 0.5);
+    __s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a2 * _sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_);
+    _lever_p_3 = std::pow(lever, 3);
+    __s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r_ = (-1 * _a2_p_2 * _lever_p_3 * _sin_l_theta0_r_);
+    _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r_ = (a1 * lever * _a2_p_3 * _sin_l_theta0_r_);
+    __s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r_ = (-1 * a1 * a2 * _lever_p_3 * _sin_l_theta0_r_);
+    _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ = (_lever_p_5_m_sin_l_theta0_r_ + __s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r_ + _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r_ + __s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r_);
+    _2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    __s_a1_p_2 = (-1 * _a1_p_2);
+    __s_a1_p_2_a_lever_p_2 = (_lever_p_2 + __s_a1_p_2);
+    _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ = std::pow(__s_a1_p_2_a_lever_p_2, -0.5);
+    __s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a1 * _sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_);
+    __s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r_ = (-1 * _a1_p_2 * _lever_p_3 * _sin_l_theta0_r_);
+    _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r_ = (a2 * lever * _a1_p_3 * _sin_l_theta0_r_);
+    _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ = (_lever_p_5_m_sin_l_theta0_r_ + __s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r_ + _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r_ + __s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r_);
+    _2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _a1_m_a2 = (a1 * a2);
+    _a1_m_a2_a_lever_p_2 = (_lever_p_2 + _a1_m_a2);
+    _1_d__l_a1_m_a2_a_lever_p_2_r_ = (1 / _a1_m_a2_a_lever_p_2);
+    __s_lever_p_4 = (-1 * _lever_p_4);
+    _a1_p_2_m_a2_p_2 = (_a1_p_2 * _a2_p_2);
+    _a1_p_2_m_a2_p_2_s_lever_p_4 = (__s_lever_p_4 + _a1_p_2_m_a2_p_2);
+    _cos_l_theta0_r_ = std::cos(theta0);
+    _cos_l_theta0_r__p_2 = (_cos_l_theta0_r_ * _cos_l_theta0_r_);
+    __s_2_m_lever_p_4_m_cos_l_theta0_r__p_2 = (-2 * _lever_p_4 * _cos_l_theta0_r__p_2);
+    _a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2 = (_a1_p_2 * _lever_p_2 * _cos_l_theta0_r__p_2);
+    _a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2 = (_a2_p_2 * _lever_p_2 * _cos_l_theta0_r__p_2);
+    __s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4 = (_lever_p_4 + __s_a1_p_2_m_a2_p_2 + __s_2_m_lever_p_4_m_cos_l_theta0_r__p_2 + _a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2 + _a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2);
+    __l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = (_a1_p_2_m_a2_p_2_s_lever_p_4 * __s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4);
+    _a1_m_lever_p_2 = (a1 * _lever_p_2);
+    _a2_m_lever_p_2 = (a2 * _lever_p_2);
+    __s_a1_m_a2_p_2 = (-1 * a1 * _a2_p_2);
+    __s_a1_p_2_m_a2 = (-1 * a2 * _a1_p_2);
+    __s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2 = (_a1_m_lever_p_2 + _a2_m_lever_p_2 + __s_a1_m_a2_p_2 + __s_a1_p_2_m_a2);
+    __l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2 = (__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2 * __s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2);
+    _lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2 = (_lever_p_2 * __l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2 * _sin_l_theta0_r__p_2);
+    _lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = (__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ + _lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2);
+    _sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = std::pow(_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_, 0.5);
+    __l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _a1_m_a2_a_lever_p_2);
+    _a1_a_a2 = (a1 + a2);
+    _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ = (lever * _a1_a_a2 * __s_a1_p_2_m_a2_p_2_a_lever_p_4 * _sin_l_theta0_r_);
+    _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ + _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_);
+    _2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d__l_a1_m_a2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    _1_d__l__s_a2_p_2_a_lever_p_2_r_ = (1 / __s_a2_p_2_a_lever_p_2);
+    __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ = std::pow(__s_a1_p_2_m_a2_p_2_a_lever_p_4, -2);
+    __l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 = (_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-2 * _1_d__l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2);
+    _1_s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (1 + __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-2 * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    _1_d_lever = (1 / lever);
+    _4_m_lever_p_2_m_sin_l_theta0_r__p_2 = (4 * _lever_p_2 * _sin_l_theta0_r__p_2);
+    _1_d__l__s_a1_p_2_a_lever_p_2_r_ = (1 / __s_a1_p_2_a_lever_p_2);
+    __l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 = (_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-4 * _lever_p_2 * _1_d__l__s_a1_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 * _sin_l_theta0_r__p_2);
+    __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-4 * _lever_p_2 * _1_d__l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 * _sin_l_theta0_r__p_2);
+    _4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (_4_m_lever_p_2_m_sin_l_theta0_r__p_2 + __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ + __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ = std::pow(_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_, 0.5);
+    _1_d_sin_l_theta0_r_ = (1 / _sin_l_theta0_r_);
+    __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = (-1 * _1_d_lever * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ * _1_d_sin_l_theta0_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    __s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-2 * _1_d__l__s_a1_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2);
+    _1_s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (1 + __s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = (-1 * _1_d_lever * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ * _1_d_sin_l_theta0_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = (_1_d_lever * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ * _1_d_sin_l_theta0_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = (_1_d_lever * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ * _1_d_sin_l_theta0_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_);
+    _lever_p__l__s_2_r_ = std::pow(lever, -2);
+    _2_m_lever_p_2 = (2 * _lever_p_2);
+    __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-4 * _lever_p_2 * _1_d__l__s_a1_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2);
+    __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (-4 * _lever_p_2 * _1_d__l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * __l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2);
+    _2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (_2_m_lever_p_2 + __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ + __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    __l_2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__d__l_2_m_lever_p_2_r_ = (0.5 * _lever_p__l__s_2_r_ * _2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    _a2_p_3_m_lever_m_sin_l_theta0_r_ = (lever * _a2_p_3 * _sin_l_theta0_r_);
+    __s_a2_m_lever_p_3_m_sin_l_theta0_r_ = (-1 * a2 * _lever_p_3 * _sin_l_theta0_r_);
+    _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = std::pow(__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8, -0.5);
+    __s_a1_m_lever_p_6 = (-1 * a1 * _lever_p_6);
+    __s_2_m_a1_p_3_m_a2_p_4 = (-2 * _a1_p_3 * _a2_p_4);
+    _a1_m_a2_p_4_m_lever_p_2 = (a1 * _a2_p_4 * _lever_p_2);
+    _a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (a2 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    __s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-1 * _a2_p_3 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2 = (2 * a1 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _2_m_a1_p_3_m_a2_p_2_m_lever_p_2 = (2 * _a1_p_3 * _a2_p_2 * _lever_p_2);
+    __s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-3 * a2 * _a1_p_2 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    __s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-2 * a1 * _a2_p_2 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2 = (3 * _a1_p_2 * _a2_p_3 * _lever_p_2 * _sin_l_theta0_r__p_2);
+    __s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (__s_a1_m_lever_p_6 + __s_2_m_a1_p_3_m_a2_p_4 + _a1_m_a2_p_4_m_lever_p_2 + _a2_m_lever_p_6_m_sin_l_theta0_r__p_2 + __s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 + _2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2 + _2_m_a1_p_3_m_a2_p_2_m_lever_p_2 + __s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 + __s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 + _3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2);
+    __s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a2 * _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * __s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2);
+    _a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (_a2_p_3_m_lever_m_sin_l_theta0_r_ + __s_a2_m_lever_p_3_m_sin_l_theta0_r_ + __s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_);
+    _2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a1 * lever * _a2_p_2 * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    __s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * _sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_);
+    __s_a1_m_lever_p_3_m_sin_l_theta0_r_ = (-1 * a1 * _lever_p_3 * _sin_l_theta0_r_);
+    __s_a2_m_lever_p_6 = (-1 * a2 * _lever_p_6);
+    __s_2_m_a1_p_4_m_a2_p_3 = (-2 * _a1_p_4 * _a2_p_3);
+    _a1_m_lever_p_6_m_sin_l_theta0_r__p_2 = (a1 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _a1_p_4_m_a2_m_lever_p_2 = (a2 * _a1_p_4 * _lever_p_2);
+    __s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-1 * _a1_p_3 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = (2 * a2 * _lever_p_6 * _sin_l_theta0_r__p_2);
+    _2_m_a1_p_2_m_a2_p_3_m_lever_p_2 = (2 * _a1_p_2 * _a2_p_3 * _lever_p_2);
+    __s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-3 * a1 * _a2_p_2 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    __s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = (-2 * a2 * _a1_p_2 * _lever_p_4 * _sin_l_theta0_r__p_2);
+    _3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2 = (3 * _a1_p_3 * _a2_p_2 * _lever_p_2 * _sin_l_theta0_r__p_2);
+    __s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6 = (__s_a2_m_lever_p_6 + __s_2_m_a1_p_4_m_a2_p_3 + _a1_m_lever_p_6_m_sin_l_theta0_r__p_2 + _a1_p_4_m_a2_m_lever_p_2 + __s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 + _2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 + _2_m_a1_p_2_m_a2_p_3_m_lever_p_2 + __s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 + __s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 + _3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2);
+    __s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a2 * _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * __s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6);
+    __s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r_ = (-2 * a2 * _lever_p_3 * _sin_l_theta0_r_);
+    _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r_ = (3 * a1 * lever * _a2_p_2 * _sin_l_theta0_r_);
+    _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_a1_m_lever_p_3_m_sin_l_theta0_r_ + __s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r_ + _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r_);
+    _2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * _sin_l_theta0_r_);
+    __l__s_a2_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ = std::pow(__s_a2_p_2_a_lever_p_2, -1.5);
+    _2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * a2 * lever * __l__s_a2_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a2 * lever * _a1_p_2 * _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    __s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a1 * _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * __s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2);
+    __s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r_ = (-2 * a1 * _lever_p_3 * _sin_l_theta0_r_);
+    _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r_ = (3 * a2 * lever * _a1_p_2 * _sin_l_theta0_r_);
+    _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ + __s_a2_m_lever_p_3_m_sin_l_theta0_r_ + __s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r_ + _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r_);
+    _2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * _sin_l_theta0_r_);
+    __l__s_a1_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ = std::pow(__s_a1_p_2_a_lever_p_2, -1.5);
+    _2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * a1 * lever * __l__s_a1_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a1 * lever * _a2_p_2 * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    _a1_p_3_m_lever_m_sin_l_theta0_r_ = (lever * _a1_p_3 * _sin_l_theta0_r_);
+    __s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (-1 * a1 * _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * __s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6);
+    _a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = (_a1_p_3_m_lever_m_sin_l_theta0_r_ + __s_a1_m_lever_p_3_m_sin_l_theta0_r_ + __s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_);
+    _2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a2 * lever * _a1_p_2 * _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    _a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (a2 * _sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_);
+    _lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ = (lever * __s_a1_p_2_m_a2_p_2_a_lever_p_4 * _sin_l_theta0_r_);
+    _1_d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = std::pow(_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_, -0.5);
+    __s_2_m_a1_m_a2_p_2 = (-2 * a1 * _a2_p_2);
+    _2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2 = (2 * a1 * _lever_p_2 * _cos_l_theta0_r__p_2);
+    __s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2 = (__s_2_m_a1_m_a2_p_2 + _2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2);
+    __l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = (0.5 * _a1_p_2_m_a2_p_2_s_lever_p_4 * __s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2);
+    _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = (a1 * _a2_p_2 * __s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4);
+    __s_2_m_a2_p_2 = (-2 * _a2_p_2);
+    __s_4_m_a1_m_a2 = (-4 * a1 * a2);
+    __s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2 = (__s_2_m_a2_p_2 + _2_m_lever_p_2 + __s_4_m_a1_m_a2);
+    _lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2 = (0.5 * _lever_p_2 * _sin_l_theta0_r__p_2 * __s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2 * __s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2);
+    _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = (__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 + _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ + _lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2);
+    __l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (_1_d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _a1_m_a2_a_lever_p_2 * _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2);
+    __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_ = (-2 * a1 * lever * _a2_p_2 * _a1_a_a2 * _sin_l_theta0_r_);
+    __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ + _lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ + __l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ + __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_);
+    _2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d__l_a1_m_a2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    __l_a1_m_a2_a_lever_p_2_r__p__l__s_2_r_ = std::pow(_a1_m_a2_a_lever_p_2, -2);
+    __s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (-2 * a2 * lever * __l_a1_m_a2_a_lever_p_2_r__p__l__s_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a1 * lever * _a2_p_2 * _1_d__l_a1_m_a2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + __s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+    _a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (a1 * _sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_);
+    __s_2_m_a1_p_2_m_a2 = (-2 * a2 * _a1_p_2);
+    _2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2 = (2 * a2 * _lever_p_2 * _cos_l_theta0_r__p_2);
+    __s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2 = (__s_2_m_a1_p_2_m_a2 + _2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2);
+    __l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = (0.5 * _a1_p_2_m_a2_p_2_s_lever_p_4 * __s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2);
+    _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = (a2 * _a1_p_2 * __s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4);
+    __s_2_m_a1_p_2 = (-2 * _a1_p_2);
+    __s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2 = (__s_2_m_a1_p_2 + _2_m_lever_p_2 + __s_4_m_a1_m_a2);
+    _lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2 = (0.5 * _lever_p_2 * _sin_l_theta0_r__p_2 * __s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2 * __s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2);
+    _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = (__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 + _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ + _lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2);
+    __l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (_1_d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _a1_m_a2_a_lever_p_2 * _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2);
+    __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_ = (-2 * a2 * lever * _a1_p_2 * _a1_a_a2 * _sin_l_theta0_r_);
+    __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = (_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ + _lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ + __l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ + __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_);
+    _2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (2 * lever * _1_d__l_a1_m_a2_a_lever_p_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    __s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (-2 * a1 * lever * __l_a1_m_a2_a_lever_p_2_r__p__l__s_2_r_ * _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ * _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = (4 * a2 * lever * _a1_p_2 * _1_d__l_a1_m_a2_a_lever_p_2_r_ * __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ * _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ * _sin_l_theta0_r_);
+    _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = (_2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + __s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ + _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_);
+
+    ex = _2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    ey = _2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    ez = _2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    exx = _1_s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_;
+    exy = __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_;
+    exz = __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_;
+    eyx = __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_;
+    eyy = _1_s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_;
+    eyz = __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_;
+    ezx = _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_;
+    ezy = _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_;
+    ezz = __l_2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__d__l_2_m_lever_p_2_r_;
+    jx1 = _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jx2 = _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jy1 = _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jy2 = _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jz1 = _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jz2 = _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_;
+    jrx1 = _lever_p_2;
+    jrx2 = _lever_p_2;
+    jry1 = _lever_p_2;
+    jry2 = _lever_p_2;
+    jrz1 = _lever_p_2;
+    jrz2 = _lever_p_2;
+}
+
+}
diff --git a/VirtualRobot/Nodes/FourBar/Expressions.h b/VirtualRobot/Nodes/FourBar/Expressions.h
new file mode 100644
index 0000000000000000000000000000000000000000..343951a9eaab780373bdb5c54fae82532e0a0947
--- /dev/null
+++ b/VirtualRobot/Nodes/FourBar/Expressions.h
@@ -0,0 +1,251 @@
+/*
+ * This file was generated automatically on 2022-06-09 10:41.
+ */
+
+#pragma once
+
+
+namespace VirtualRobot::four_bar
+{
+
+class Expressions
+{
+public:
+
+    void compute(double a1, double a2, double lever, double theta0);
+
+    // Input arguments:
+    double a1 = 0;
+    double a2 = 0;
+    double lever = 0;
+    double theta0 = 0;
+
+    // Results:
+    double ex = 0;
+    double ey = 0;
+    double ez = 0;
+    double exx = 0;
+    double exy = 0;
+    double exz = 0;
+    double eyx = 0;
+    double eyy = 0;
+    double eyz = 0;
+    double ezx = 0;
+    double ezy = 0;
+    double ezz = 0;
+    double jx1 = 0;
+    double jx2 = 0;
+    double jy1 = 0;
+    double jy2 = 0;
+    double jz1 = 0;
+    double jz2 = 0;
+    double jrx1 = 0;
+    double jrx2 = 0;
+    double jry1 = 0;
+    double jry2 = 0;
+    double jrz1 = 0;
+    double jrz2 = 0;
+
+    // Intermediate expressions:
+    double _lever_p_2 = 0;
+    double _a2_p_2 = 0;
+    double __s_a2_p_2 = 0;
+    double __s_a2_p_2_a_lever_p_2 = 0;
+    double _1_d_sqrt_l__s_a2_p_2_a_lever_p_2_r_ = 0;
+    double _lever_p_4 = 0;
+    double _a1_p_2 = 0;
+    double __s_a1_p_2_m_a2_p_2 = 0;
+    double __s_a1_p_2_m_a2_p_2_a_lever_p_4 = 0;
+    double _1_d__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r_ = 0;
+    double _lever_p_5 = 0;
+    double _sin_l_theta0_r_ = 0;
+    double _lever_p_5_m_sin_l_theta0_r_ = 0;
+    double _lever_p_8 = 0;
+    double _lever_p_6 = 0;
+    double __s_a1_p_2_m_lever_p_6 = 0;
+    double _a1_p_4 = 0;
+    double _a2_p_4 = 0;
+    double __s_a1_p_4_m_a2_p_4 = 0;
+    double __s_a2_p_2_m_lever_p_6 = 0;
+    double _sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_lever_p_8_m_sin_l_theta0_r__p_2 = 0;
+    double _a1_p_2_m_a2_p_4_m_lever_p_2 = 0;
+    double _a1_p_4_m_a2_p_2_m_lever_p_2 = 0;
+    double _2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _a2_p_3 = 0;
+    double __s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _a1_p_3 = 0;
+    double __s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2 = 0;
+    double __s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8 = 0;
+    double _sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _lever_p_3 = 0;
+    double __s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r_ = 0;
+    double __s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ = 0;
+    double _2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __s_a1_p_2 = 0;
+    double __s_a1_p_2_a_lever_p_2 = 0;
+    double _1_d_sqrt_l__s_a1_p_2_a_lever_p_2_r_ = 0;
+    double __s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r_ = 0;
+    double _a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r_ = 0;
+    double _2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _a1_m_a2 = 0;
+    double _a1_m_a2_a_lever_p_2 = 0;
+    double _1_d__l_a1_m_a2_a_lever_p_2_r_ = 0;
+    double __s_lever_p_4 = 0;
+    double _a1_p_2_m_a2_p_2 = 0;
+    double _a1_p_2_m_a2_p_2_s_lever_p_4 = 0;
+    double _cos_l_theta0_r_ = 0;
+    double _cos_l_theta0_r__p_2 = 0;
+    double __s_2_m_lever_p_4_m_cos_l_theta0_r__p_2 = 0;
+    double _a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double _a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double __s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4 = 0;
+    double __l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = 0;
+    double _a1_m_lever_p_2 = 0;
+    double _a2_m_lever_p_2 = 0;
+    double __s_a1_m_a2_p_2 = 0;
+    double __s_a1_p_2_m_a2 = 0;
+    double __s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2 = 0;
+    double __l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2 = 0;
+    double _lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2 = 0;
+    double _lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = 0;
+    double _sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double __l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double _a1_a_a2 = 0;
+    double _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ = 0;
+    double _lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double _2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _1_d__l__s_a2_p_2_a_lever_p_2_r_ = 0;
+    double __l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p__l__s_2_r_ = 0;
+    double __l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 = 0;
+    double __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _1_s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double __s_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _1_d_lever = 0;
+    double _4_m_lever_p_2_m_sin_l_theta0_r__p_2 = 0;
+    double _1_d__l__s_a1_p_2_a_lever_p_2_r_ = 0;
+    double __l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2 = 0;
+    double __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r_ = 0;
+    double _1_d_sin_l_theta0_r_ = 0;
+    double __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = 0;
+    double __s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _1_s_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double __s_sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = 0;
+    double _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = 0;
+    double _sqrt_l_4_m_lever_p_2_m_sin_l_theta0_r__p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_m_sin_l_theta0_r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__d__l_lever_m_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__r_ = 0;
+    double _lever_p__l__s_2_r_ = 0;
+    double _2_m_lever_p_2 = 0;
+    double __s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double __s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double __l_2_m_lever_p_2_s_4_m_lever_p_2_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_4_m_lever_p_2_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__p_2_d__l__l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__r__d__l_2_m_lever_p_2_r_ = 0;
+    double _a2_p_3_m_lever_m_sin_l_theta0_r_ = 0;
+    double __s_a2_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _1_d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_a1_m_lever_p_6 = 0;
+    double __s_2_m_a1_p_3_m_a2_p_4 = 0;
+    double _a1_m_a2_p_4_m_lever_p_2 = 0;
+    double _a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double __s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a1_p_3_m_a2_p_2_m_lever_p_2 = 0;
+    double __s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double __s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a2_p_3_m_lever_m_sin_l_theta0_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_a1_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double __s_a2_m_lever_p_6 = 0;
+    double __s_2_m_a1_p_4_m_a2_p_3 = 0;
+    double _a1_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _a1_p_4_m_a2_m_lever_p_2 = 0;
+    double __s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2 = 0;
+    double _2_m_a1_p_2_m_a2_p_3_m_lever_p_2 = 0;
+    double __s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2 = 0;
+    double _3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6 = 0;
+    double __s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r_ = 0;
+    double _3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __l__s_a2_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ = 0;
+    double _2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a2_m_lever_m__l_a1_m_a2_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a2_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_m_a2_p_2_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_2_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a2_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a2_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double __s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r_ = 0;
+    double _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r_ = 0;
+    double _3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __l__s_a1_p_2_a_lever_p_2_r__p__l__s_1_t_5_r_ = 0;
+    double _2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_a1_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l__l__s_a1_p_2_a_lever_p_2_r__p_1_t_5_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l_3_m_a1_p_2_m_a2_m_lever_m_sin_l_theta0_r__s_2_m_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_3_m_a2_p_4_a_2_m_a1_p_3_m_a2_p_2_m_lever_p_2_a_3_m_a1_p_2_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_3_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_a2_p_4_m_lever_p_2_s_2_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_m_lever_p_6_s_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__s_a2_m_lever_p_3_m_sin_l_theta0_r__s_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _a1_p_3_m_lever_m_sin_l_theta0_r_ = 0;
+    double __s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r_ = 0;
+    double _2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_a1_p_3_m_a2_m_lever_m_sin_l_theta0_r__s_a1_p_2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_a2_m_lever_p_3_m_sin_l_theta0_r__s_a1_m_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__a_lever_p_5_m_sin_l_theta0_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__a_2_m_lever_m__l_a1_p_3_m_lever_m_sin_l_theta0_r__s_a1_m_lever_p_3_m_sin_l_theta0_r__s_a1_m__l__s_2_m_a1_p_4_m_a2_p_3_a_a1_p_4_m_a2_m_lever_p_2_a_3_m_a1_p_3_m_a2_p_2_m_lever_p_2_m_sin_l_theta0_r__p_2_s_a1_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_a2_p_3_m_lever_p_2_s_2_m_a1_p_2_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_s_3_m_a1_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_m_lever_p_6_r__d_sqrt_l__s_a1_p_4_m_a2_p_4_a_a1_p_4_m_a2_p_2_m_lever_p_2_a_2_m_a1_p_3_m_a2_p_3_m_lever_p_2_m_sin_l_theta0_r__p_2_s_2_m_a1_p_3_m_a2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_a1_p_2_m_a2_p_4_m_lever_p_2_s_2_m_a1_p_2_m_a2_p_2_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a1_p_2_m_lever_p_6_s_2_m_a1_m_a2_p_3_m_lever_p_4_m_sin_l_theta0_r__p_2_a_2_m_a1_m_a2_m_lever_p_6_m_sin_l_theta0_r__p_2_a_2_m_a2_p_2_m_lever_p_6_m_sin_l_theta0_r__p_2_s_a2_p_2_m_lever_p_6_s_2_m_lever_p_8_m_sin_l_theta0_r__p_2_a_lever_p_8_r__r__m_sin_l_theta0_r__d__l_sqrt_l__s_a1_p_2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double _lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r_ = 0;
+    double _1_d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double __s_2_m_a1_m_a2_p_2 = 0;
+    double _2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double __l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = 0;
+    double _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = 0;
+    double __s_2_m_a2_p_2 = 0;
+    double __s_4_m_a1_m_a2 = 0;
+    double __s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2 = 0;
+    double _lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2 = 0;
+    double _a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = 0;
+    double __l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_ = 0;
+    double __s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double _2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __l_a1_m_a2_a_lever_p_2_r__p__l__s_2_r_ = 0;
+    double __s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_m_a2_p_2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_m_a2_p_2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a2_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_m_a2_p_2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_4_m_a1_m_a2_s_2_m_a2_p_2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_m_a2_p_2_a_2_m_a1_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double __s_2_m_a1_p_2_m_a2 = 0;
+    double _2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double __s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2 = 0;
+    double __l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = 0;
+    double _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r_ = 0;
+    double __s_2_m_a1_p_2 = 0;
+    double __s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2 = 0;
+    double _lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2 = 0;
+    double _a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2 = 0;
+    double __l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r_ = 0;
+    double __s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r_ = 0;
+    double _2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double __s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r_ = 0;
+    double _4_m_a1_p_2_m_a2_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__p_2_r__s_2_m_a1_m_lever_m__l_lever_m__l_a1_a_a2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__p_2_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r__a_2_m_lever_m__l__s_2_m_a1_p_2_m_a2_m_lever_m__l_a1_a_a2_r__m_sin_l_theta0_r__a_a1_m_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__a_lever_m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__m_sin_l_theta0_r__a__l_a1_m_a2_a_lever_p_2_r__m__l_a1_p_2_m_a2_m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__a_lever_p_2_m__l__s_2_m_a1_p_2_s_4_m_a1_m_a2_a_2_m_lever_p_2_r__m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__m_sin_l_theta0_r__p_2_d_2_a__l__s_2_m_a1_p_2_m_a2_a_2_m_a2_m_lever_p_2_m_cos_l_theta0_r__p_2_r__m__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__d_2_r__d_sqrt_l_lever_p_2_m__l__s_a1_p_2_m_a2_s_a1_m_a2_p_2_a_a1_m_lever_p_2_a_a2_m_lever_p_2_r__p_2_m_sin_l_theta0_r__p_2_a__l_a1_p_2_m_a2_p_2_s_lever_p_4_r__m__l__s_a1_p_2_m_a2_p_2_a_a1_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_a_a2_p_2_m_lever_p_2_m_cos_l_theta0_r__p_2_s_2_m_lever_p_4_m_cos_l_theta0_r__p_2_a_lever_p_4_r__r__r__m_sin_l_theta0_r__d__l__l_a1_m_a2_a_lever_p_2_r__m__l__s_a1_p_2_m_a2_p_2_a_lever_p_4_r__r_ = 0;
+
+};
+
+}
diff --git a/VirtualRobot/Nodes/FourBar/Joint.cpp b/VirtualRobot/Nodes/FourBar/Joint.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..bbc01c202580014bd07329b13b1c563a7e192d61
--- /dev/null
+++ b/VirtualRobot/Nodes/FourBar/Joint.cpp
@@ -0,0 +1,89 @@
+#include "Joint.h"
+
+#include <cmath>
+
+#include <Eigen/Core>
+#include <Eigen/Geometry>
+
+#include <SimoxUtility/math/convert/deg_to_rad.h>
+#include <SimoxUtility/math/pose/pose.h>
+
+
+namespace VirtualRobot::four_bar
+{
+
+    Joint::Joint(double theta0, const Dimensions& dimensions) : theta0(theta0), dims(dimensions)
+    {
+    }
+
+
+    // void Joint::computeFkOfPosition(double p1, double p2)
+    // {
+    //     fk.compute(p1, p2, lever, theta0);
+    // }
+
+
+    // void Joint::computeFkOfPosition(const Eigen::Vector2d& p12)
+    // {
+    //     computeFkOfPosition(p12(0), p12(1));
+    // }
+
+
+    void
+    Joint::computeFkOfAngle(const double theta)
+    {
+        // computeFkOfPosition(angleToPosition(alpha12));
+        // transformation.setIdentity();
+
+        // move from passive to active joint
+        const Eigen::Translation3d passive_T_active_base(Eigen::Vector3d::UnitX() * dims.shank);
+
+        // apply rotation of this active joint
+        const Eigen::AngleAxisd active_base_T_eef{theta0 + theta, Eigen::Vector3d::UnitZ()};
+
+        transformation = passive_T_active_base * active_base_T_eef;
+    }
+
+
+    Eigen::Vector3d
+    Joint::getEndEffectorTranslation() const
+    {
+        return transformation.translation();
+        // return Eigen::Vector3d{fk.ex, fk.ey, fk.ez};
+    }
+
+
+    Eigen::Matrix3d
+    Joint::getEndEffectorRotation() const
+    {
+        return transformation.rotation();
+        // r_wrist_to_base = np.array([[exx, eyx, ezx], [exy, eyy, ezy], [exz, eyz, ezz]])
+        // Eigen::Matrix3d ori;
+        // ori << fk.exx, fk.eyx, fk.ezx, fk.exy, fk.eyy, fk.ezy, fk.exz, fk.eyz, fk.ezz;
+        // return ori;
+    }
+
+
+    Eigen::Matrix4d
+    Joint::getEndEffectorTransform() const
+    {
+        return transformation.matrix();
+    }
+
+
+    Joint::Jacobian
+    Joint::getJacobian() const
+    {
+        // FIXME implement
+        Joint::Jacobian jacobian;
+        jacobian << fk.jx1, fk.jx2, fk.jy1, fk.jy2, fk.jz1, fk.jz2, fk.jrx1, fk.jrx2, fk.jry1,
+            fk.jry2, fk.jrz1, fk.jrz2;
+        return jacobian;
+    }
+
+    // Eigen::Vector2d Joint::angleToPosition(const Eigen::Vector2d& alpha) const
+    // {
+    //     return lever * Eigen::sin((alpha + Eigen::Vector2d::Constant(theta0)).array());
+    // }
+
+} // namespace VirtualRobot::four_bar
diff --git a/VirtualRobot/Nodes/FourBar/Joint.h b/VirtualRobot/Nodes/FourBar/Joint.h
new file mode 100644
index 0000000000000000000000000000000000000000..56271ee299ded7f2bb50e50b5047ecb9ce1f674c
--- /dev/null
+++ b/VirtualRobot/Nodes/FourBar/Joint.h
@@ -0,0 +1,100 @@
+#pragma once
+
+#include <cmath>
+
+#include <Eigen/Core>
+#include <Eigen/Geometry>
+
+#include "Expressions.h"
+
+
+namespace VirtualRobot::four_bar
+{
+
+    // this class represents the four bar mechanisms; in particular the actuated joint
+    class Joint
+    {
+    public:
+        using Jacobian = Eigen::Matrix<double, 6, 1>;
+
+    public:
+        struct Dimensions;
+
+        Joint(double theta0, const Dimensions& dimensions);
+
+        struct Dimensions
+        {
+            double shank = 280;
+            double p1 = 84.375;
+            double p2 = 270;
+            double p3 = 45;
+
+            // C.15
+            double
+            k1() const
+            {
+                return shank / p1;
+            }
+
+            // C.16
+            double
+            k2() const
+            {
+                return shank / p3;
+            }
+
+            // C.17
+            double
+            k3() const
+            {
+                constexpr auto squared = [](const double t){ return t * t; };
+
+                return (squared(shank) + squared(p1) + squared(p3) - squared(p2)) / (2 * p1 * p3);
+            }
+        };
+
+        double
+        psi(const double theta)
+        {
+            const double k1 = dims.k1();
+            const double k2 = dims.k2();
+            const double k3 = dims.k3();
+
+            const double cosTheta = std::cos(theta);
+            const double sinTheta = std::sin(theta);
+
+            const double A = k1 * cosTheta + k2 + k3 + cosTheta; // C.34
+            const double B = -2 * sinTheta; // C.35
+            const double C = k1 * cosTheta - k2 + k3 - cosTheta; // C.36
+
+            const double psi = 2 * std::atan((-B + std::sqrt(B * B - 4 * A * C)) / (2 * A)); // C.39
+
+            return psi;
+        }
+
+        // compute pose of actuated joint in passive joint frame
+        void computeFkOfAngle(double theta);
+
+
+        Eigen::Vector3d getEndEffectorTranslation() const;
+        Eigen::Matrix3d getEndEffectorRotation() const;
+        Eigen::Matrix4d getEndEffectorTransform() const;
+        Jacobian getJacobian() const;
+
+        // Eigen::Vector2d angleToPosition(const Eigen::Vector2d& alpha) const;
+
+
+    public:
+        const double theta0;
+        const Dimensions dims; 
+
+        double limitLo = 0;
+        double limitHi = 0;
+
+
+        Expressions fk;
+
+        Eigen::Isometry3d transformation = Eigen::Isometry3d::Identity();
+    };
+
+} // namespace VirtualRobot::four_bar
diff --git a/VirtualRobot/Nodes/RobotNode.cpp b/VirtualRobot/Nodes/RobotNode.cpp
index 2107a7b3d1de25b922ca77ce3296f05e1ef3b467..33dae5a5141a3c19c488bf0f6a7c8236a49e2998 100644
--- a/VirtualRobot/Nodes/RobotNode.cpp
+++ b/VirtualRobot/Nodes/RobotNode.cpp
@@ -662,6 +662,11 @@ namespace VirtualRobot
     {
         return false;
     }
+    
+    bool RobotNode::isFourBarJoint() const
+    {
+        return false;
+    }
 
     void RobotNode::setLimitless(bool limitless)
     {
@@ -888,7 +893,7 @@ namespace VirtualRobot
 
     bool RobotNode::isJoint() const
     {
-        return isRotationalJoint() or isTranslationalJoint() or isHemisphereJoint();
+        return isRotationalJoint() or isTranslationalJoint() or isHemisphereJoint() or isFourBarJoint();
     }
 
     void RobotNode::setMaxTorque(float maxTo)
diff --git a/VirtualRobot/Nodes/RobotNode.h b/VirtualRobot/Nodes/RobotNode.h
index 9bd9cd44eecee77fa3e81356ddea146242578b15..454973471658e6eecc0698d000484b2e83b69dc8 100644
--- a/VirtualRobot/Nodes/RobotNode.h
+++ b/VirtualRobot/Nodes/RobotNode.h
@@ -95,7 +95,7 @@ namespace VirtualRobot
             The internal matrices and visualizations are updated accordingly.
             If you intend to update multiple joints, use \ref setJointValueNoUpdate(float) for faster access.
         */
-        void setJointValue(float q);
+        virtual void setJointValue(float q);
 
         /*!
             All children and their children (and so on) are collected.
@@ -228,6 +228,7 @@ namespace VirtualRobot
         virtual bool isTranslationalJoint() const;
         virtual bool isRotationalJoint() const;
         virtual bool isHemisphereJoint() const;
+        virtual bool isFourBarJoint() const;
 
         /**
          * @param limitless wheter this node has joint limits or not.
diff --git a/VirtualRobot/Nodes/RobotNodeFourBar.cpp b/VirtualRobot/Nodes/RobotNodeFourBar.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..d33363e916e4156ca3aea208a786df7ae47a6bb4
--- /dev/null
+++ b/VirtualRobot/Nodes/RobotNodeFourBar.cpp
@@ -0,0 +1,498 @@
+#include "RobotNodeFourBar.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <Eigen/Geometry>
+#include <Eigen/src/Geometry/AngleAxis.h>
+
+#include <SimoxUtility/math/pose/pose.h>
+#include <SimoxUtility/meta/enum/EnumNames.hpp>
+
+#include "Nodes/FourBar/Joint.h"
+#include "Nodes/Sensor.h"
+#include "Robot.h"
+#include "VirtualRobotException.h"
+
+
+namespace VirtualRobot
+{
+    namespace four_bar
+    {
+        extern const simox::meta::EnumNames<RobotNodeFourBar::Role> RoleNames = {
+            {RobotNodeFourBar::Role::PASSIVE, "passive"},
+            {RobotNodeFourBar::Role::ACTIVE, "active"},
+        };
+
+    } // namespace four_bar
+
+
+    VirtualRobot::RobotNodeFourBar::RobotNodeFourBar() = default;
+
+    RobotNodeFourBar::Role
+    RobotNodeFourBar::RoleFromString(const std::string& string)
+    {
+        return four_bar::RoleNames.from_name(string);
+    }
+
+    RobotNodeFourBar::RobotNodeFourBar(RobotWeakPtr rob,
+                                       const std::string& name,
+                                       float jointLimitLo,
+                                       float jointLimitHi,
+                                       const Eigen::Matrix4f& preJointTransform,
+                                       const Eigen::Vector3f& axis,
+                                       VisualizationNodePtr visualization,
+                                       CollisionModelPtr collisionModel,
+                                       float jointValueOffset,
+                                       const SceneObject::Physics& physics,
+                                       CollisionCheckerPtr colChecker,
+                                       RobotNodeType type) :
+        RobotNode(rob,
+                  name,
+                  jointLimitLo,
+                  jointLimitHi,
+                  visualization,
+                  collisionModel,
+                  jointValueOffset,
+                  physics,
+                  colChecker,
+                  type)
+    {
+        (void)axis;
+
+        initialized = false;
+        optionalDHParameter.isSet = false;
+        localTransformation = preJointTransform;
+        checkValidRobotNodeType();
+    }
+
+
+    RobotNodeFourBar::RobotNodeFourBar(RobotWeakPtr rob,
+                                       const std::string& name,
+                                       float jointLimitLo,
+                                       float jointLimitHi,
+                                       float a,
+                                       float d,
+                                       float alpha,
+                                       float theta,
+                                       VisualizationNodePtr visualization,
+                                       CollisionModelPtr collisionModel,
+                                       float jointValueOffset,
+                                       const SceneObject::Physics& physics,
+                                       CollisionCheckerPtr colChecker,
+                                       RobotNodeType type) :
+        RobotNode(rob,
+                  name,
+                  jointLimitLo,
+                  jointLimitHi,
+                  visualization,
+                  collisionModel,
+                  jointValueOffset,
+                  physics,
+                  colChecker,
+                  type)
+    {
+        initialized = false;
+        optionalDHParameter.isSet = true;
+        optionalDHParameter.setAInMM(a);
+        optionalDHParameter.setDInMM(d);
+        optionalDHParameter.setAlphaRadian(alpha, true);
+        optionalDHParameter.setThetaRadian(theta, true);
+
+        // compute DH transformation matrices
+        // Eigen::Matrix4f RotTheta = Eigen::Matrix4f::Identity();
+        // RotTheta(0, 0) = cos(theta);
+        // RotTheta(0, 1) = -sin(theta);
+        // RotTheta(1, 0) = sin(theta);
+        // RotTheta(1, 1) = cos(theta);
+        // Eigen::Matrix4f TransD = Eigen::Matrix4f::Identity();
+        // TransD(2, 3) = d;
+        // Eigen::Matrix4f TransA = Eigen::Matrix4f::Identity();
+        // TransA(0, 3) = a;
+        // Eigen::Matrix4f RotAlpha = Eigen::Matrix4f::Identity();
+        // RotAlpha(1, 1) = cos(alpha);
+        // RotAlpha(1, 2) = -sin(alpha);
+        // RotAlpha(2, 1) = sin(alpha);
+        // RotAlpha(2, 2) = cos(alpha);
+
+        // localTransformation = RotTheta * TransD * TransA * RotAlpha;
+        localTransformation.setIdentity();
+        checkValidRobotNodeType();
+    }
+
+    void
+    RobotNodeFourBar::setJointValueNoUpdate(float q)
+    {
+        std::cout << "RobotNodeFourBar: setting joint value no update " << q << std::endl;
+
+        if (active)
+        {
+            // update the passive joint
+            const float psi = active->math.joint.psi(q);
+            active->passive->setJointValueNoUpdate(-psi); // FIXME make joint axis consistent
+            RobotNode::setJointValueNoUpdate(q);
+        }
+        else
+        {
+            RobotNode::setJointValueNoUpdate(q);
+        }
+    }
+
+
+    void
+    RobotNodeFourBar::setJointValue(float q)
+    {
+        // We must update the preceeding node (the passive node).
+        // This usually causes issues as the order to update the kinematic chain is strict.
+        std::cout << "RobotNodeFourBar: setting joint value " << getName()  << " " << q << std::endl;
+
+        std::cout << "RobotNodeFourBar: active? " << active.has_value() << std::endl;
+
+        // update this node (without the global / internal pose!)
+        {
+            RobotPtr r = getRobot();
+            VR_ASSERT(r);
+            WriteLockPtr lock = r->getWriteLock();
+            setJointValueNoUpdate(q);
+        }
+
+        if (active)
+        {
+            std::cout << "RobotNodeFourBar: triggering update of passive joint " << std::endl;
+
+            // update all nodes including this one
+            active->passive->updatePose(true);
+        }
+    }
+
+
+    RobotNodeFourBar::~RobotNodeFourBar() = default;
+
+
+    void
+    RobotNodeFourBar::setXmlInfo(const XmlInfo& info)
+    {
+        this->xmlInfo = info;
+
+        VR_ASSERT(second.has_value());
+        switch (info.role)
+        {
+            case Role::PASSIVE:
+                std::cout << "Role: passive" << std::endl;
+                first.emplace(First{});
+                // first->math.joint.setConstants(0, info.theta0);
+                break;
+
+            case Role::ACTIVE:
+                std::cout << "Role: active" << std::endl;
+                active.emplace(
+                    Second{.passive = nullptr,
+                           .math = JointMath{.joint = four_bar::Joint{jointValueOffset,
+                                                                      info.dimensions.value()}}});
+                break;
+        }
+    }
+
+
+    bool
+    RobotNodeFourBar::initialize(SceneObjectPtr parent, const std::vector<SceneObjectPtr>& children)
+    {
+        VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(),
+                          std::stringstream() << first.has_value() << " / " << second.has_value());
+
+        // The second node needs to store a reference to the first node.
+        // Whenever the joint value has changed, the passive joint will be updated.
+        if (active)
+        {
+            std::cout << "Initializing active four bar joint" << std::endl;
+
+            VR_ASSERT_MESSAGE(not second->first, "Second must not be initialized yet.");
+
+            VirtualRobot::SceneObjectPtr currentParent = parent;
+
+            while (currentParent != nullptr)
+            {
+                auto* firstNode = dynamic_cast<RobotNodeFourBar*>(currentParent.get());
+
+                // TODO traverse all nodes until the passive four bar node is reached.
+                // TODO then, keep a list of all nodes that have to be updated if the passive node is updated
+                // => all child nodes except this one. It is important to not trigger an update of this node as it would
+                // result in infinite recursion.
+
+                // RobotNodeFourBar* secondNode = this;
+
+                // if (not(firstNode and firstNode->first))
+                // {
+                //     std::stringstream ss;
+                //     ss << "The parent of a four_bar joint with role '"
+                //        << four_bar::RoleNames.to_name(Role::ACTIVE) << "' "
+                //        << "must be a four_bar joint with role '"
+                //        << four_bar::RoleNames.to_name(Role::PASSIVE) << "' ";
+                //     THROW_VR_EXCEPTION(ss.str());
+                // }
+
+                if(firstNode == nullptr)
+                {
+                    currentParent = currentParent->getParent();
+                    std::cout << "Parent does not match (yet).";
+                    continue;
+                }
+
+                std::cout << "Parent matches.";
+
+                // Save pointer to firstNode
+                active->passive = firstNode;
+
+                // initialize the passive node
+                const float psi = active->math.joint.psi(getJointValue());
+                active->passive->setJointValueNoUpdate(-psi);
+
+                // Set up robot node parameters.
+                {
+                    // const four_bar::Joint& joint = active->math.joint;
+
+                    // firstNode->jointLimitLo = joint.limitLo;
+                    // secondNode->jointLimitLo = joint.limitLo;
+
+                    // firstNode->jointLimitHi = joint.limitHi;
+                    // secondNode->jointLimitHi = joint.limitHi;
+                }
+
+                break;
+            }
+        }
+
+        return RobotNode::initialize(parent, children);
+    }
+
+
+    void
+    RobotNodeFourBar::JointMath::update(const float theta)
+    {
+        // if (actuators != this->actuators)
+        // {
+        joint.computeFkOfAngle(theta);
+        // }
+    }
+
+
+    void
+    RobotNodeFourBar::updateTransformationMatrices(const Eigen::Matrix4f& parentPose)
+    {
+        VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(),
+                          std::stringstream() << first.has_value() << " / " << second.has_value());
+
+        std::cout << "Updating RobotNodeFourBar::updateTransformationMatrices" << std::endl;
+
+        Eigen::Isometry3f tmp = Eigen::Isometry3f::Identity();
+
+        const auto jV = this->getJointValue();
+
+        if (active)
+        {
+            std::cout << "active: joint value " << jV << std::endl;
+
+            active->math.update(jV);
+            tmp = active->math.joint.getEndEffectorTransform().cast<float>();
+        }
+        else // passive
+        {
+            std::cout << "passive: joint value " << jV << std::endl;
+
+            tmp.linear() =
+                Eigen::AngleAxisf(jV + jointValueOffset, Eigen::Vector3f::UnitZ()).toRotationMatrix();
+        }
+
+
+        std::cout << "local transformation: " << getName() << tmp.matrix() << std::endl;
+        globalPose = parentPose * localTransformation * tmp.matrix();
+
+
+        // if (first)
+        // {
+        //     globalPose = parentPose * localTransformation;
+        // }
+        // else if (active)
+        // {
+        //     VR_ASSERT_MESSAGE(second->first, "First node must be known to second node.");
+
+        //     JointMath& math = active->math();
+        //     Eigen::Vector2f actuators(active->passive->getJointValue(), this->getJointValue());
+
+        //     math.update(actuators);
+
+        //     Eigen::Vector3d translation = math.joint.getEndEffectorTranslation();
+        //     const Eigen::Matrix3d rotation = math.joint.getEndEffectorRotation();
+        //     const Eigen::Matrix4d transform = simox::math::pose(translation, rotation);
+
+        //     // Update Second
+        //     {
+        //         this->globalPose = parentPose * localTransformation * transform.cast<float>();
+
+        //         Eigen::IOFormat iof(5, 0, " ", "\n", "    [", "]");
+        //         std::cout
+        //             << __FUNCTION__ << "() of second actuator with "
+        //             << "\n  lever = " << math.joint.lever << "\n  theta0 = " << math.joint.theta0
+        //             << "\n  radius = " << math.joint.radius << "\n  joint value = " << jointValue
+        //             << "\n  actuator (angle) = \n"
+        //             << actuators.transpose().format(iof) << "\n  actuator (pos) =  \n"
+        //             << math.joint.angleToPosition(actuators.cast<double>()).transpose().format(iof)
+        //             << "\n  local transform = \n"
+        //             << localTransformation.format(iof) << "\n  joint transform = \n"
+        //             << transform.format(iof) << std::endl;
+        //     }
+        // }
+    }
+
+
+    void
+    RobotNodeFourBar::print(bool printChildren, bool printDecoration) const
+    {
+        ReadLockPtr lock = getRobot()->getReadLock();
+        VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(),
+                          std::stringstream() << first.has_value() << " / " << second.has_value());
+
+        if (printDecoration)
+        {
+            std::cout << "******** RobotNodeFourBar ********" << std::endl;
+        }
+
+        RobotNode::print(false, false);
+
+        if (first)
+        {
+            std::cout << "* four_bar joint first node";
+        }
+        else if (active)
+        {
+            std::cout << "* four_bar joint second node";
+            std::cout << "* Transform: \n"
+                      << active->math.joint.getEndEffectorTransform() << std::endl;
+        }
+
+        if (printDecoration)
+        {
+            std::cout << "******** End RobotNodeFourBar ********" << std::endl;
+        }
+
+        if (printChildren)
+        {
+            for (const SceneObjectPtr& child : this->getChildren())
+            {
+                child->print(true, true);
+            }
+        }
+    }
+
+
+    RobotNodePtr
+    RobotNodeFourBar::_clone(const RobotPtr newRobot,
+                             const VisualizationNodePtr visualizationModel,
+                             const CollisionModelPtr collisionModel,
+                             CollisionCheckerPtr colChecker,
+                             float scaling)
+    {
+        ReadLockPtr lock = getRobot()->getReadLock();
+        Physics physics = this->physics.scale(scaling);
+
+        RobotNodeFourBarPtr result;
+        if (optionalDHParameter.isSet)
+        {
+            result.reset(new RobotNodeFourBar(newRobot,
+                                              name,
+                                              jointLimitLo,
+                                              jointLimitHi,
+                                              optionalDHParameter.aMM() * scaling,
+                                              optionalDHParameter.dMM() * scaling,
+                                              optionalDHParameter.alphaRadian(),
+                                              optionalDHParameter.thetaRadian(),
+                                              visualizationModel,
+                                              collisionModel,
+                                              jointValueOffset,
+                                              physics,
+                                              colChecker,
+                                              nodeType));
+        }
+        else
+        {
+            Eigen::Matrix4f localTransform = getLocalTransformation();
+            simox::math::position(localTransform) *= scaling;
+            result.reset(new RobotNodeFourBar(newRobot,
+                                              name,
+                                              jointLimitLo,
+                                              jointLimitHi,
+                                              localTransform,
+                                              Eigen::Vector3f::Zero(),
+                                              visualizationModel,
+                                              collisionModel,
+                                              jointValueOffset,
+                                              physics,
+                                              colChecker,
+                                              nodeType));
+        }
+
+        if(xmlInfo)
+        {
+            result->setXmlInfo(xmlInfo.value());
+        }
+
+        return result;
+    }
+
+
+    bool
+    RobotNodeFourBar::isFourBarJoint() const
+    {
+        return true;
+    }
+
+
+    void
+    RobotNodeFourBar::checkValidRobotNodeType()
+    {
+        RobotNode::checkValidRobotNodeType();
+        THROW_VR_EXCEPTION_IF(nodeType == Body || nodeType == Transform,
+                              "RobotNodeFourBar must be a JointNode or a GenericNode");
+    }
+
+
+    std::string
+    RobotNodeFourBar::_toXML(const std::string& /*modelPath*/)
+    {
+        VR_ASSERT_MESSAGE(first.has_value() xor second.has_value(),
+                          std::stringstream() << first.has_value() << " / " << second.has_value());
+
+        if (first)
+        {
+            // TODO
+            return "";
+        }
+        else
+        {
+            JointMath& math = active->math;
+
+            // FIXME implement
+
+            std::stringstream ss;
+            ss << "\t\t<Joint type='four_bar'>" << std::endl;
+            ss << "\t\t\t<four_bar theta0='" << math.joint.theta0 << "' />" << std::endl;
+            ss << "\t\t\t<limits lo='" << jointLimitLo << "' hi='" << jointLimitHi
+               << "' units='radian'/>" << std::endl;
+            ss << "\t\t\t<MaxAcceleration value='" << maxAcceleration << "'/>" << std::endl;
+            ss << "\t\t\t<MaxVelocity value='" << maxVelocity << "'/>" << std::endl;
+            ss << "\t\t\t<MaxTorque value='" << maxTorque << "'/>" << std::endl;
+            std::map<std::string, float>::iterator propIt = propagatedJointValues.begin();
+
+            while (propIt != propagatedJointValues.end())
+            {
+                ss << "\t\t\t<PropagateJointValue name='" << propIt->first << "' factor='"
+                   << propIt->second << "'/>" << std::endl;
+                propIt++;
+            }
+
+            ss << "\t\t</Joint>" << std::endl;
+            return ss.str();
+        }
+    }
+
+} // namespace VirtualRobot
diff --git a/VirtualRobot/Nodes/RobotNodeFourBar.h b/VirtualRobot/Nodes/RobotNodeFourBar.h
new file mode 100644
index 0000000000000000000000000000000000000000..23879ae9a783ec375750ddc882c3e41af0f4756c
--- /dev/null
+++ b/VirtualRobot/Nodes/RobotNodeFourBar.h
@@ -0,0 +1,180 @@
+/**
+* This file is part of Simox.
+*
+* Simox is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* Simox is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU Lesser General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    VirtualRobot
+* @author     Fabian Reister
+* @copyright  2023 Fabian Reister
+*             GNU Lesser General Public License
+*/
+#pragma once
+
+#include <optional>
+#include <string>
+#include <vector>
+
+#include <Eigen/Core>
+
+#include "../VirtualRobot.h"
+#include "Nodes/FourBar/Joint.h"
+#include "RobotNode.h"
+
+
+namespace VirtualRobot
+{
+
+    // FIXME split into two classes FourBarActive and FourBarPassive
+
+    using RobotNodeFourBarPtr = std::shared_ptr<class RobotNodeFourBar>;
+
+    class VIRTUAL_ROBOT_IMPORT_EXPORT RobotNodeFourBar : public RobotNode
+    {
+    public:
+        enum class Role
+        {
+            PASSIVE,
+            ACTIVE,
+        };
+        static Role RoleFromString(const std::string& string);
+
+        struct XmlInfo
+        {
+            Role role;
+
+            // Only set for first:
+            double theta0 = -1;
+            // double lever = -1;
+
+            std::optional<four_bar::Joint::Dimensions> dimensions;
+        };
+
+        friend class RobotFactory;
+
+        EIGEN_MAKE_ALIGNED_OPERATOR_NEW
+
+
+        RobotNodeFourBar(
+            RobotWeakPtr rob, ///< The robot
+            const std::string& name, ///< The name
+            float jointLimitLo, ///< lower joint limit
+            float jointLimitHi, ///< upper joint limit
+            const Eigen::Matrix4f&
+                preJointTransform, ///< This transformation is applied before the translation of the joint is done
+            const Eigen::Vector3f& axis, ///< The rotation axis (in local joint coord system)
+            VisualizationNodePtr visualization = nullptr, ///< A visualization model
+            CollisionModelPtr collisionModel = nullptr, ///< A collision model
+            float jointValueOffset =
+                0.0f, ///< An offset that is internally added to the joint value
+            const SceneObject::Physics& p = {}, ///< physics information
+            CollisionCheckerPtr colChecker =
+                nullptr, ///< A collision checker instance (if not set, the global col checker is used)
+            RobotNodeType type = Generic);
+
+        RobotNodeFourBar(
+            RobotWeakPtr rob, ///< The robot
+            const std::string& name, ///< The name
+            float jointLimitLo, ///< lower joint limit
+            float jointLimitHi, ///< upper joint limit
+            float a, ///< dh paramters
+            float d, ///< dh paramters
+            float alpha, ///< dh paramters
+            float theta, ///< dh paramters
+            VisualizationNodePtr visualization = nullptr, ///< A visualization model
+            CollisionModelPtr collisionModel = nullptr, ///< A collision model
+            float jointValueOffset =
+                0.0f, ///< An offset that is internally added to the joint value
+            const SceneObject::Physics& p = {}, ///< physics information
+            CollisionCheckerPtr colChecker =
+                {}, ///< A collision checker instance (if not set, the global col checker is used)
+            RobotNodeType type = Generic);
+
+        void setJointValueNoUpdate(float q) override;
+        void setJointValue(float q) override;
+
+    public:
+        ~RobotNodeFourBar() override;
+
+
+        void setXmlInfo(const XmlInfo& info);
+
+        bool initialize(SceneObjectPtr parent = nullptr,
+                        const std::vector<SceneObjectPtr>& children = {}) override;
+
+        /// Print status information.
+        void print(bool printChildren = false, bool printDecoration = true) const override;
+
+        bool isFourBarJoint() const override;
+
+
+    protected:
+        RobotNodeFourBar();
+
+        /// Derived classes add custom XML tags here
+        std::string _toXML(const std::string& modelPath) override;
+
+        /// Checks if nodeType constraints are fulfilled. Otherwise an exception is thrown.
+        /// Called on initialization.
+        void checkValidRobotNodeType() override;
+
+        void updateTransformationMatrices(const Eigen::Matrix4f& parentPose) override;
+
+        RobotNodePtr _clone(const RobotPtr newRobot,
+                            const VisualizationNodePtr visualizationModel,
+                            const CollisionModelPtr collisionModel,
+                            CollisionCheckerPtr colChecker,
+                            float scaling) override;
+
+
+    protected:
+        struct JointMath
+        {
+            /// The actuator values that were used to compute the joint math.
+            // Eigen::Vector2f actuators = Eigen::Vector2f::Constant(std::numeric_limits<float>::min());
+            /// The joint math.
+            four_bar::Joint joint;
+
+            void update(float theta);
+        };
+
+        struct First
+        {
+            // JointMath math;
+        };
+        std::optional<First> first;
+
+        struct Second
+        {
+            /// The first actuator node.
+            RobotNodeFourBar* passive = nullptr;
+
+            JointMath math;
+
+            // JointMath& math()
+            // {
+            //     return passive->first->math;
+            // }
+            // const JointMath& math() const
+            // {
+            //     return passive->first->math;
+            // }
+        };
+        std::optional<Second> active;
+
+
+
+        std::optional<XmlInfo> xmlInfo;
+    };
+
+} // namespace VirtualRobot
diff --git a/VirtualRobot/Nodes/RobotNodeFourBarFactory.cpp b/VirtualRobot/Nodes/RobotNodeFourBarFactory.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..ee9bff05cdf5c19512b9faf19f1eac8b36209895
--- /dev/null
+++ b/VirtualRobot/Nodes/RobotNodeFourBarFactory.cpp
@@ -0,0 +1,102 @@
+/**
+* @package    VirtualRobot
+* @author     Fabian Reister
+* @copyright  2023 Fabian Reister
+*/
+
+#include "RobotNodeFourBarFactory.h"
+
+#include "../CollisionDetection/CollisionModel.h"
+#include "RobotNode.h"
+#include "RobotNodeFourBar.h"
+
+
+namespace VirtualRobot
+{
+
+    RobotNodeFourBarFactory::RobotNodeFourBarFactory() = default;
+
+
+    RobotNodeFourBarFactory::~RobotNodeFourBarFactory() = default;
+
+
+    RobotNodePtr
+    RobotNodeFourBarFactory::createRobotNode(RobotPtr robot,
+                                             const std::string& nodeName,
+                                             VisualizationNodePtr visualizationModel,
+                                             CollisionModelPtr collisionModel,
+                                             float limitLow,
+                                             float limitHigh,
+                                             float jointValueOffset,
+                                             const Eigen::Matrix4f& preJointTransform,
+                                             const Eigen::Vector3f& axis,
+                                             const Eigen::Vector3f& /*translationDirection*/,
+                                             const SceneObject::Physics& physics,
+                                             RobotNode::RobotNodeType rntype) const
+    {
+        std::cout << "CREATE NEW FOUR BAR JOINT" << std::endl;
+        return std::make_shared<RobotNodeFourBar>(
+            robot,
+            nodeName,
+            limitLow,
+            limitHigh,
+            preJointTransform,
+            axis,
+            visualizationModel,
+            collisionModel,
+            jointValueOffset,
+            physics,
+            (collisionModel ? collisionModel->getCollisionChecker() : CollisionCheckerPtr()),
+            rntype);
+    }
+
+
+    RobotNodePtr
+    RobotNodeFourBarFactory::createRobotNodeDH(RobotPtr robot,
+                                               const std::string& nodeName,
+                                               VisualizationNodePtr visualizationModel,
+                                               CollisionModelPtr collisionModel,
+                                               float limitLow,
+                                               float limitHigh,
+                                               float jointValueOffset,
+                                               const DHParameter& dhParameters,
+                                               const SceneObject::Physics& physics,
+                                               RobotNode::RobotNodeType rntype) const
+    {
+        std::cout << "CREATE NEW FOUR BAR JOINT DH" << std::endl;
+        return std::make_shared<RobotNodeFourBar>(robot,
+                                                     nodeName,
+                                                     limitLow,
+                                                     limitHigh,
+                                                     dhParameters.aMM(),
+                                                     dhParameters.dMM(),
+                                                     dhParameters.alphaRadian(),
+                                                     dhParameters.thetaRadian(),
+                                                     visualizationModel,
+                                                     collisionModel,
+                                                     jointValueOffset,
+                                                     physics,
+                                                     CollisionCheckerPtr(),
+                                                     rntype);
+    }
+
+
+    RobotNodeFactory::SubClassRegistry
+        RobotNodeFourBarFactory::registry(RobotNodeFourBarFactory::getName(),
+                                          &RobotNodeFourBarFactory::createInstance);
+
+
+    std::string
+    RobotNodeFourBarFactory::getName()
+    {
+        return "four_bar";
+    }
+
+
+    std::shared_ptr<RobotNodeFactory>
+    RobotNodeFourBarFactory::createInstance(void*)
+    {
+        return std::make_shared<RobotNodeFourBarFactory>();
+    }
+
+} // namespace VirtualRobot
diff --git a/VirtualRobot/Nodes/RobotNodeFourBarFactory.h b/VirtualRobot/Nodes/RobotNodeFourBarFactory.h
new file mode 100644
index 0000000000000000000000000000000000000000..02a210d073b3ed5ec86c4151b3abf682b8020191
--- /dev/null
+++ b/VirtualRobot/Nodes/RobotNodeFourBarFactory.h
@@ -0,0 +1,84 @@
+/**
+* This file is part of Simox.
+*
+* Simox is free software; you can redistribute it and/or modify
+* it under the terms of the GNU Lesser General Public License as
+* published by the Free Software Foundation; either version 2 of
+* the License, or (at your option) any later version.
+*
+* Simox is distributed in the hope that it will be useful, but
+* WITHOUT ANY WARRANTY; without even the implied warranty of
+* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+* GNU Lesser General Public License for more details.
+*
+* You should have received a copy of the GNU Lesser General Public License
+* along with this program. If not, see <http://www.gnu.org/licenses/>.
+*
+* @package    VirtualRobot
+* @author     Fabian Reister
+* @copyright  2023 Fabian Reister
+*             GNU Lesser General Public License
+*/
+#pragma once
+
+#include "../SceneObject.h"
+#include "../VirtualRobot.h"
+#include "RobotNodeFactory.h"
+
+
+namespace VirtualRobot
+{
+    class RobotNode;
+
+    class VIRTUAL_ROBOT_IMPORT_EXPORT RobotNodeFourBarFactory : public RobotNodeFactory
+    {
+    public:
+        RobotNodeFourBarFactory();
+        ~RobotNodeFourBarFactory() override;
+
+        /**
+         * Create a VirtualRobot::RobotNodeFourBar.
+         *
+         * \return instance of VirtualRobot::RobotNodeFourBar.
+         */
+        RobotNodePtr
+        createRobotNode(RobotPtr robot,
+                        const std::string& nodeName,
+                        VisualizationNodePtr visualizationModel,
+                        CollisionModelPtr collisionModel,
+                        float limitLow,
+                        float limitHigh,
+                        float jointValueOffset,
+                        const Eigen::Matrix4f& preJointTransform,
+                        const Eigen::Vector3f& axis,
+                        const Eigen::Vector3f& translationDirection,
+                        const SceneObject::Physics& p = SceneObject::Physics(),
+                        RobotNode::RobotNodeType rntype = RobotNode::Generic) const override;
+
+        /**
+         * Create a VirtualRobot::RobotNodeFourBar from DH parameters.
+         *
+         * \return instance of VirtualRobot::RobotNodeFourBar.
+         */
+        RobotNodePtr
+        createRobotNodeDH(RobotPtr robot,
+                          const std::string& nodeName,
+                          VisualizationNodePtr visualizationModel,
+                          CollisionModelPtr collisionModel,
+                          float limitLow,
+                          float limitHigh,
+                          float jointValueOffset,
+                          const DHParameter& dhParameters,
+                          const SceneObject::Physics& p = SceneObject::Physics(),
+                          RobotNode::RobotNodeType rntype = RobotNode::Generic) const override;
+
+        // AbstractFactoryMethod
+    public:
+        static std::string getName();
+        static std::shared_ptr<RobotNodeFactory> createInstance(void*);
+
+    private:
+        static SubClassRegistry registry;
+    };
+
+} // namespace VirtualRobot
diff --git a/VirtualRobot/Nodes/RobotNodeHemisphere.h b/VirtualRobot/Nodes/RobotNodeHemisphere.h
index 343a20b86d913cb5cea392912e44b5829aa50d25..91e32bd11ac6ccc7c90461ce9dacd19860746e06 100644
--- a/VirtualRobot/Nodes/RobotNodeHemisphere.h
+++ b/VirtualRobot/Nodes/RobotNodeHemisphere.h
@@ -140,13 +140,12 @@ namespace VirtualRobot
                 ) override;
 
         RobotNodePtr
-        _clone(
-                const RobotPtr newRobot,
-                const VisualizationNodePtr visualizationModel,
-                const CollisionModelPtr collisionModel,
-                CollisionCheckerPtr colChecker,
-                float scaling
-                ) override;
+        _clone(const RobotPtr newRobot,
+               const VisualizationNodePtr visualizationModel,
+               const CollisionModelPtr collisionModel,
+               CollisionCheckerPtr colChecker,
+               float scaling
+               ) override;
 
 
     public:
@@ -186,4 +185,3 @@ namespace VirtualRobot
     };
 
 } // namespace VirtualRobot
-
diff --git a/VirtualRobot/Robot.cpp b/VirtualRobot/Robot.cpp
index 2945832a5f56d06054004234315f14eb776e6804..ea1b6d6e698d919d9b0d8c1de7941b063238a20c 100644
--- a/VirtualRobot/Robot.cpp
+++ b/VirtualRobot/Robot.cpp
@@ -960,7 +960,7 @@ namespace VirtualRobot
 
         for (const auto& rn : this->getRobotNodes())
         {
-            if (rn->isTranslationalJoint() || rn->isRotationalJoint())
+            if (rn->isJoint())
             {
                 r->setConfig(rn, rn->getJointValue());
             }
@@ -1119,6 +1119,7 @@ namespace VirtualRobot
 
         for (size_t i = 0; i < rn.size(); i++)
         {
+            VR_INFO << rn[i]->getName() << ": " <<  jointValues[i];
             rn[i]->setJointValueNoUpdate(jointValues[i]);
         }
 
diff --git a/VirtualRobot/XML/RobotIO.cpp b/VirtualRobot/XML/RobotIO.cpp
index 6b5808efc0744a4f3cb575a71c5901a2cfc3957e..e49fb3e89337a0ce30b5e182a388eb007551ffca 100644
--- a/VirtualRobot/XML/RobotIO.cpp
+++ b/VirtualRobot/XML/RobotIO.cpp
@@ -16,11 +16,12 @@
 #include "../Visualization/TriMeshModel.h"
 #include "../RobotConfig.h"
 #include "../RuntimeEnvironment.h"
+#include "Nodes/RobotNodeFourBar.h"
 #include "VirtualRobot.h"
 #include "rapidxml.hpp"
 #include "mujoco/RobotMjcf.h"
 #include <VirtualRobot/Import/URDF/SimoxURDFFactory.h>
-
+#include <VirtualRobot/Nodes/FourBar/Joint.h>
 #include <SimoxUtility/xml/rapidxml/rapidxml_print.hpp>
 #include <SimoxUtility/filesystem/remove_trailing_separator.h>
 #include <SimoxUtility/math/convert/deg_to_rad.h>
@@ -251,6 +252,7 @@ namespace VirtualRobot
         Eigen::Vector3f scaleVisuFactor = Eigen::Vector3f::Zero();
 
         std::optional<RobotNodeHemisphere::XmlInfo> hemisphere;
+        std::optional<RobotNodeFourBar::XmlInfo> fourBarXmlInfo;
 
         while (node)
         {
@@ -473,6 +475,40 @@ namespace VirtualRobot
                     break;
                 }
             }
+            else if (nodeName == "four_bar")
+            {
+                fourBarXmlInfo.emplace();
+
+                std::string roleString = processStringAttribute("role", node, true);
+                roleString = simox::alg::to_lower(roleString);
+                try
+                {
+                    fourBarXmlInfo->role = RobotNodeFourBar::RoleFromString(roleString);
+                }
+                catch (const std::out_of_range& e)
+                {
+                    THROW_VR_EXCEPTION("Invalid role in four_bar joint: " << e.what())
+                }
+
+                const rapidxml::xml_node<>* dimensionsNode = node->first_node("dimensions", 0, false);
+
+                if(fourBarXmlInfo->role == RobotNodeFourBar::Role::ACTIVE)
+                {
+                    if(dimensionsNode == nullptr)
+                    {
+                        THROW_VR_EXCEPTION("Missing <dimensions> node for four_bar joint.");
+                    }
+                
+                    fourBarXmlInfo->dimensions = four_bar::Joint::Dimensions
+                    {
+                        .shank = getFloatByAttributeName(dimensionsNode, "shank"),
+                        .p1 = getFloatByAttributeName(dimensionsNode, "p1"),
+                        .p2 = getFloatByAttributeName(dimensionsNode, "p2"),
+                        .p3 = getFloatByAttributeName(dimensionsNode, "p3")
+                    };
+                }
+                
+            }
             else
             {
                 THROW_VR_EXCEPTION("XML definition <" << nodeName << "> not supported in <Joint> tag of RobotNode <" << robotNodeName << ">." << endl);
@@ -587,6 +623,12 @@ namespace VirtualRobot
             node->setXmlInfo(hemisphere.value());
         }
 
+        if(robotNode->isFourBarJoint() and fourBarXmlInfo.has_value())
+        {
+            auto node = std::dynamic_pointer_cast<RobotNodeFourBar>(robotNode);
+            node->setXmlInfo(fourBarXmlInfo.value());
+        }
+
         if (scaleVisu)
         {
             RobotNodePrismaticPtr rnPM = std::dynamic_pointer_cast<RobotNodePrismatic>(robotNode);
diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
index 2326f0b53e784773254c4d3fae3d16dda58bd9dc..b3128f36b46069c2889b720c12a755b949d6a461 100644
--- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
+++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp
@@ -615,6 +615,8 @@ void showRobotWindow::jointValueChanged(int pos)
             + static_cast<float>(pos) / 1000.0f
             * (currentRobotNodes[nr]->getJointLimitHi()
                - currentRobotNodes[nr]->getJointLimitLo());
+
+    std::cout << "Setting joint value " << fPos << " for joint " << currentRobotNodes[nr]->getName() << std::endl;
     robot->setJointValue(currentRobotNodes[nr], fPos);
     UI.lcdNumberJointValue->display(static_cast<double>(fPos));
 
@@ -816,8 +818,8 @@ void showRobotWindow::updatRobotInfo()
     UI.checkBoxFullModel->setChecked(true);
     UI.checkBoxPhysicsCoM->setChecked(false);
     UI.checkBoxPhysicsInertia->setChecked(false);
-    UI.checkBoxRobotCoordSystems->setChecked(false);
-    UI.checkBoxShowCoordSystem->setChecked(false);
+    UI.checkBoxRobotCoordSystems->setChecked(true);
+    UI.checkBoxShowCoordSystem->setChecked(true);
     UI.checkBoxStructure->setChecked(false);
 
     // get nodes
@@ -874,6 +876,8 @@ void showRobotWindow::robotStructure()
     }
 
     structureEnabled = UI.checkBoxStructure->checkState() == Qt::Checked;
+    structureEnabled = true;
+
     robot->showStructure(structureEnabled);
     // rebuild visualization
     rebuildVisualization();
@@ -887,6 +891,7 @@ void showRobotWindow::robotCoordSystems()
     }
 
     bool robotAllCoordsEnabled = UI.checkBoxRobotCoordSystems->checkState() == Qt::Checked;
+    robotAllCoordsEnabled = true;
     robot->showCoordinateSystems(robotAllCoordsEnabled);
     // rebuild visualization
     rebuildVisualization();
diff --git a/python/four_bar_mechanism/equations.ipynb b/python/four_bar_mechanism/equations.ipynb
new file mode 100644
index 0000000000000000000000000000000000000000..5cc71b36d64d86bc9d2419765ef83aace4cc37f5
--- /dev/null
+++ b/python/four_bar_mechanism/equations.ipynb
@@ -0,0 +1,502 @@
+{
+ "cells": [
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "# Jacobian of Four-Bar Mechanism \n",
+    "\n",
+    "The knee joint is actuated but the ankle joint is passive.  \n",
+    "\n",
+    "## Todo's\n",
+    "\n",
+    "  - consider $\\theta_0$"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 57,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "import sympy as sp\n",
+    "sp.init_printing(use_latex='mathjax')\n",
+    "\n",
+    "from sympy import symbols, sin, cos, sqrt, asin, atan\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 71,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# Actuation (knee)\n",
+    "theta = symbols('theta')\n",
+    "\n",
+    "# Passive joint (ankle) \n",
+    "psi = symbols('psi')\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 59,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "\n",
+    "# Constants defined by geometry.\n",
+    "theta0 = symbols('theta0')\n",
+    "\n",
+    "shank, p1, p2, p3 = symbols('shank p1 p2 p3')\n",
+    "\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 60,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# Manually specified structure of equations. We first introduce variables based on the kinematic structure only.\n",
+    "# These can easily be precomputed in code. Here, they are just mentioned as a reference.\n",
+    "\n",
+    "k1 = shank / p1\n",
+    "k2 = shank / p3\n",
+    "k3 = (shank**2 + p1**2 + p3**2 - p2**2 ) / (2 * p1 * p3)\n",
+    "\n",
+    "\n",
+    "# directly use these variables\n",
+    "k1, k2, k3 = symbols('k1 k2 k3')\n"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "## Relationship between ankle ($\\psi$) and knee ($\\theta$)"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 61,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "\n",
+    "# some helpers\n",
+    "cT = cos(theta)\n",
+    "sT = sin(theta)\n",
+    "\n",
+    "\n",
+    "A = k1 * cT + k2 + k3 + cT # C.34\n",
+    "B = -2*sT # C.35\n",
+    "C = k1 * cT - k2 + k3 - cT # C.36\n",
+    "\n",
+    "# ankle\n",
+    "psi = 2 * atan((-B + sqrt(B * B - 4 * A * C)) / (2 * A)) #  C.39\n",
+    "\n",
+    "psi = sp.simplify(psi)\n",
+    "\n",
+    "psi_of_theta = psi\n",
+    "\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 62,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/latex": [
+       "$\\displaystyle 2 \\operatorname{atan}{\\left(\\frac{\\sqrt{- k_{1}^{2} \\cos^{2}{\\left(\\theta \\right)} - 2 k_{1} k_{3} \\cos{\\left(\\theta \\right)} + k_{2}^{2} + 2 k_{2} \\cos{\\left(\\theta \\right)} - k_{3}^{2} + 1} + \\sin{\\left(\\theta \\right)}}{k_{1} \\cos{\\left(\\theta \\right)} + k_{2} + k_{3} + \\cos{\\left(\\theta \\right)}} \\right)}$"
+      ],
+      "text/plain": [
+       "      ⎛   ______________________________________________________________      \n",
+       "      ⎜  ╱     2    2                         2                   2           \n",
+       "      ⎜╲╱  - k₁ ⋅cos (θ) - 2⋅k₁⋅k₃⋅cos(θ) + k₂  + 2⋅k₂⋅cos(θ) - k₃  + 1  + sin\n",
+       "2⋅atan⎜───────────────────────────────────────────────────────────────────────\n",
+       "      ⎝                       k₁⋅cos(θ) + k₂ + k₃ + cos(θ)                    \n",
+       "\n",
+       "   ⎞\n",
+       "   ⎟\n",
+       "(θ)⎟\n",
+       "───⎟\n",
+       "   ⎠"
+      ]
+     },
+     "execution_count": 62,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "psi"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "### Derivatives"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 63,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/latex": [
+       "$\\displaystyle \\frac{2 \\left(\\frac{\\left(k_{1} \\sin{\\left(\\theta \\right)} + \\sin{\\left(\\theta \\right)}\\right) \\left(\\sqrt{- k_{1}^{2} \\cos^{2}{\\left(\\theta \\right)} - 2 k_{1} k_{3} \\cos{\\left(\\theta \\right)} + k_{2}^{2} + 2 k_{2} \\cos{\\left(\\theta \\right)} - k_{3}^{2} + 1} + \\sin{\\left(\\theta \\right)}\\right)}{\\left(k_{1} \\cos{\\left(\\theta \\right)} + k_{2} + k_{3} + \\cos{\\left(\\theta \\right)}\\right)^{2}} + \\frac{\\frac{k_{1}^{2} \\sin{\\left(\\theta \\right)} \\cos{\\left(\\theta \\right)} + k_{1} k_{3} \\sin{\\left(\\theta \\right)} - k_{2} \\sin{\\left(\\theta \\right)}}{\\sqrt{- k_{1}^{2} \\cos^{2}{\\left(\\theta \\right)} - 2 k_{1} k_{3} \\cos{\\left(\\theta \\right)} + k_{2}^{2} + 2 k_{2} \\cos{\\left(\\theta \\right)} - k_{3}^{2} + 1}} + \\cos{\\left(\\theta \\right)}}{k_{1} \\cos{\\left(\\theta \\right)} + k_{2} + k_{3} + \\cos{\\left(\\theta \\right)}}\\right)}{\\frac{\\left(\\sqrt{- k_{1}^{2} \\cos^{2}{\\left(\\theta \\right)} - 2 k_{1} k_{3} \\cos{\\left(\\theta \\right)} + k_{2}^{2} + 2 k_{2} \\cos{\\left(\\theta \\right)} - k_{3}^{2} + 1} + \\sin{\\left(\\theta \\right)}\\right)^{2}}{\\left(k_{1} \\cos{\\left(\\theta \\right)} + k_{2} + k_{3} + \\cos{\\left(\\theta \\right)}\\right)^{2}} + 1}$"
+      ],
+      "text/plain": [
+       "  ⎛                                                                           \n",
+       "  ⎜                                                                           \n",
+       "  ⎜                                                                           \n",
+       "  ⎜                     ⎛   __________________________________________________\n",
+       "  ⎜                     ⎜  ╱     2    2                         2             \n",
+       "  ⎜(k₁⋅sin(θ) + sin(θ))⋅⎝╲╱  - k₁ ⋅cos (θ) - 2⋅k₁⋅k₃⋅cos(θ) + k₂  + 2⋅k₂⋅cos(θ\n",
+       "2⋅⎜───────────────────────────────────────────────────────────────────────────\n",
+       "  ⎜                                                               2           \n",
+       "  ⎝                                 (k₁⋅cos(θ) + k₂ + k₃ + cos(θ))            \n",
+       "──────────────────────────────────────────────────────────────────────────────\n",
+       "                                                                              \n",
+       "                                                ⎛   __________________________\n",
+       "                                                ⎜  ╱     2    2               \n",
+       "                                                ⎝╲╱  - k₁ ⋅cos (θ) - 2⋅k₁⋅k₃⋅c\n",
+       "                                                ──────────────────────────────\n",
+       "                                                                              \n",
+       "                                                                       (k₁⋅cos\n",
+       "\n",
+       "                                      2                                       \n",
+       "                                    k₁ ⋅sin(θ)⋅cos(θ) + k₁⋅k₃⋅sin(θ) - k₂⋅sin(\n",
+       "                         ─────────────────────────────────────────────────────\n",
+       "____________         ⎞      __________________________________________________\n",
+       "      2              ⎟     ╱     2    2                         2             \n",
+       ") - k₃  + 1  + sin(θ)⎠   ╲╱  - k₁ ⋅cos (θ) - 2⋅k₁⋅k₃⋅cos(θ) + k₂  + 2⋅k₂⋅cos(θ\n",
+       "────────────────────── + ─────────────────────────────────────────────────────\n",
+       "                                                k₁⋅cos(θ) + k₂ + k₃ + cos(θ)  \n",
+       "                                                                              \n",
+       "──────────────────────────────────────────────────────────────────────────────\n",
+       "                                              2                               \n",
+       "____________________________________         ⎞                                \n",
+       "          2                   2              ⎟                                \n",
+       "os(θ) + k₂  + 2⋅k₂⋅cos(θ) - k₃  + 1  + sin(θ)⎠                                \n",
+       "─────────────────────────────────────────────── + 1                           \n",
+       "                       2                                                      \n",
+       "(θ) + k₂ + k₃ + cos(θ))                                                       \n",
+       "\n",
+       "                     ⎞\n",
+       "θ)                   ⎟\n",
+       "──────────── + cos(θ)⎟\n",
+       "____________         ⎟\n",
+       "      2              ⎟\n",
+       ") - k₃  + 1          ⎟\n",
+       "─────────────────────⎟\n",
+       "                     ⎟\n",
+       "                     ⎠\n",
+       "──────────────────────\n",
+       "                      \n",
+       "                      \n",
+       "                      \n",
+       "                      \n",
+       "                      \n",
+       "                      \n",
+       "                      "
+      ]
+     },
+     "execution_count": 63,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "from sympy import diff\n",
+    "\n",
+    "dpsi_dtheta = diff(psi, theta)\n",
+    "\n",
+    "dpsi_dtheta"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 64,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# We can implement the term dpsi_dtheta now in code. Therefore, we assume from now on that it is given.\n",
+    "\n",
+    "from sympy import Function\n",
+    "psi = Function('psi')(theta)"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "## Coordinate systems"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 65,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/latex": [
+       "$\\displaystyle \\operatorname{CoordSys3D}\\left(knee_base, \\left( \\left[\\begin{matrix}1 & 0 & 0\\\\0 & 1 & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  (shank)\\mathbf{\\hat{i}_{ankle}}\\right), \\operatorname{CoordSys3D}\\left(ankle, \\left( \\left[\\begin{matrix}\\cos{\\left(\\psi{\\left(\\theta \\right)} \\right)} & - \\sin{\\left(\\psi{\\left(\\theta \\right)} \\right)} & 0\\\\\\sin{\\left(\\psi{\\left(\\theta \\right)} \\right)} & \\cos{\\left(\\psi{\\left(\\theta \\right)} \\right)} & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  \\mathbf{\\hat{0}}\\right), \\operatorname{CoordSys3D}\\left(base, \\left( \\left[\\begin{matrix}1 & 0 & 0\\\\0 & 1 & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  \\mathbf{\\hat{0}}\\right)\\right)\\right)\\right)$"
+      ],
+      "text/plain": [
+       "knee_base"
+      ]
+     },
+     "execution_count": 65,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "\n",
+    "from sympy.vector import CoordSys3D, AxisOrienter\n",
+    "from sympy import Matrix\n",
+    "\n",
+    "# The reference system at the origin of the ankle. It is defined as follows:\n",
+    "# -z is the rotation axis of the joint\n",
+    "# x points upwards (away from the platform, aligned with the global z axis)\n",
+    "B = CoordSys3D('base')\n",
+    "\n",
+    "orienter_psi = AxisOrienter(psi, -B.k )\n",
+    "\n",
+    "# coordinate system of the ankle joint (after applying the joint rotation)\n",
+    "T_ankle = B.orient_new('ankle', (orienter_psi, ))\n",
+    "\n",
+    "# helper coordinate system at the origin of the knee after applying the knee rotation\n",
+    "T_knee_base = T_ankle.locate_new('knee_base', shank * T_ankle.i )\n",
+    "\n",
+    "T_knee_base\n",
+    "\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 66,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/latex": [
+       "$\\displaystyle \\operatorname{CoordSys3D}\\left(knee, \\left( \\left[\\begin{matrix}\\cos{\\left(\\theta \\right)} & \\sin{\\left(\\theta \\right)} & 0\\\\- \\sin{\\left(\\theta \\right)} & \\cos{\\left(\\theta \\right)} & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  \\mathbf{\\hat{0}}\\right), \\operatorname{CoordSys3D}\\left(knee_base, \\left( \\left[\\begin{matrix}1 & 0 & 0\\\\0 & 1 & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  (shank)\\mathbf{\\hat{i}_{ankle}}\\right), \\operatorname{CoordSys3D}\\left(ankle, \\left( \\left[\\begin{matrix}\\cos{\\left(\\psi{\\left(\\theta \\right)} \\right)} & - \\sin{\\left(\\psi{\\left(\\theta \\right)} \\right)} & 0\\\\\\sin{\\left(\\psi{\\left(\\theta \\right)} \\right)} & \\cos{\\left(\\psi{\\left(\\theta \\right)} \\right)} & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  \\mathbf{\\hat{0}}\\right), \\operatorname{CoordSys3D}\\left(base, \\left( \\left[\\begin{matrix}1 & 0 & 0\\\\0 & 1 & 0\\\\0 & 0 & 1\\end{matrix}\\right], \\  \\mathbf{\\hat{0}}\\right)\\right)\\right)\\right)\\right)$"
+      ],
+      "text/plain": [
+       "knee"
+      ]
+     },
+     "execution_count": 66,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "\n",
+    "orienter_theta = AxisOrienter(theta, B.k )\n",
+    "\n",
+    "# coordinate system of the knee after applying the rotation\n",
+    "T_knee = T_knee_base.orient_new('knee', (orienter_theta, ))\n",
+    "\n",
+    "T_knee"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": null,
+   "metadata": {},
+   "outputs": [],
+   "source": []
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 67,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "# express the end effector in the knee joint coordinate system (T_knee). This captures the forward kinematics of child joints.\n",
+    "x, y, z, alpha, beta, gamma = symbols(\"x y z alpha beta gamma\")\n",
+    "\n",
+    "from sympy.vector import BodyOrienter, Point\n",
+    "euler = BodyOrienter(alpha, beta, gamma, rot_order=\"XYZ\")\n",
+    "\n",
+    "P_eef = T_knee.orient_new(\"EEF\", euler, location=(T_knee.i * x + T_knee.j * y + T_knee.k * z))\n",
+    "\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 68,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "pos_vect = P_eef.origin.position_wrt(B)\n",
+    "\n",
+    "# express the EEF in the base coordinate system (ankle base)\n",
+    "p_eef = pos_vect.to_matrix(B)\n",
+    "\n",
+    "# o = P_eef.rotation_matrix(B)"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "# Jacobian\n",
+    "\n",
+    "Pose of the end-effector\n",
+    "$$\n",
+    "p_{eef} = (x,y,z,\\alpha, \\beta, \\gamma )^T\n",
+    "$$\n",
+    "\n",
+    "The Jacobian $J \\in \\mathrm{R}^{6x1}$\n",
+    "$$\n",
+    "J = \\frac{\\partial p_{eef}}{\\partial \\theta}\n",
+    "$$\n"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 69,
+   "metadata": {},
+   "outputs": [
+    {
+     "data": {
+      "text/latex": [
+       "$\\displaystyle \\left[\\begin{matrix}- shank \\sin{\\left(\\psi{\\left(\\theta \\right)} \\right)} \\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} + x \\left(\\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} - 1\\right) \\sin{\\left(\\theta - \\psi{\\left(\\theta \\right)} \\right)} + y \\left(\\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} - 1\\right) \\cos{\\left(\\theta - \\psi{\\left(\\theta \\right)} \\right)}\\\\- shank \\cos{\\left(\\psi{\\left(\\theta \\right)} \\right)} \\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} - x \\left(\\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} - 1\\right) \\cos{\\left(\\theta - \\psi{\\left(\\theta \\right)} \\right)} + y \\left(\\frac{d}{d \\theta} \\psi{\\left(\\theta \\right)} - 1\\right) \\sin{\\left(\\theta - \\psi{\\left(\\theta \\right)} \\right)}\\\\0\\end{matrix}\\right]$"
+      ],
+      "text/plain": [
+       "⎡                  d            ⎛d           ⎞                   ⎛d           \n",
+       "⎢- shank⋅sin(ψ(θ))⋅──(ψ(θ)) + x⋅⎜──(ψ(θ)) - 1⎟⋅sin(θ - ψ(θ)) + y⋅⎜──(ψ(θ)) - 1\n",
+       "⎢                  dθ           ⎝dθ          ⎠                   ⎝dθ          \n",
+       "⎢                                                                             \n",
+       "⎢                  d            ⎛d           ⎞                   ⎛d           \n",
+       "⎢- shank⋅cos(ψ(θ))⋅──(ψ(θ)) - x⋅⎜──(ψ(θ)) - 1⎟⋅cos(θ - ψ(θ)) + y⋅⎜──(ψ(θ)) - 1\n",
+       "⎢                  dθ           ⎝dθ          ⎠                   ⎝dθ          \n",
+       "⎢                                                                             \n",
+       "⎣                                             0                               \n",
+       "\n",
+       "⎞              ⎤\n",
+       "⎟⋅cos(θ - ψ(θ))⎥\n",
+       "⎠              ⎥\n",
+       "               ⎥\n",
+       "⎞              ⎥\n",
+       "⎟⋅sin(θ - ψ(θ))⎥\n",
+       "⎠              ⎥\n",
+       "               ⎥\n",
+       "               ⎦"
+      ]
+     },
+     "execution_count": 69,
+     "metadata": {},
+     "output_type": "execute_result"
+    }
+   ],
+   "source": [
+    "from sympy import diff\n",
+    "\n",
+    "# position part of the Jacobian\n",
+    "dp_dtheta = diff(p_eef, theta)\n",
+    "dp_dtheta = dp_dtheta.simplify()\n",
+    "\n",
+    "dp_dtheta\n"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "the expression $\\frac{\\partial \\mathbf{p}}{\\partial \\theta}$ above yields $\\frac{\\partial x}{\\partial\\theta}$ and $\\frac{\\partial y}{\\partial\\theta}$. $\\frac{\\partial z}{\\partial\\theta}$ is $0$.\n",
+    "\n",
+    "\n",
+    "To obtain the orientation part, we only need to consider the angle $\\gamma$ as the joint mechanism is 2D (rotatation around z axis). In other words  $\\frac{\\partial \\alpha}{\\partial\\theta} = \\frac{\\partial \\beta}{\\partial\\theta} = 0$\n",
+    "\n",
+    "\n",
+    "\n",
+    "It is\n",
+    "\n",
+    "$$ \n",
+    "\\gamma = \\gamma_{0} -\\psi + \\theta\n",
+    "$$\n",
+    "\n",
+    "Partial derivative:\n",
+    "\n",
+    "$$\n",
+    "\\frac{\\partial \\gamma}{\\partial\\theta} = 1 - \\frac{\\partial \\psi}{\\partial\\theta} \n",
+    "$$\n",
+    "\n",
+    "\n"
+   ]
+  },
+  {
+   "attachments": {},
+   "cell_type": "markdown",
+   "metadata": {},
+   "source": [
+    "# Automatic code generation\n",
+    "\n",
+    "It is advantageous to implement the equations above by hand. Sine and cosine terms can be computed once for improved efficiency.\n",
+    "\n",
+    "*The following is just for reference*"
+   ]
+  },
+  {
+   "cell_type": "code",
+   "execution_count": 70,
+   "metadata": {},
+   "outputs": [],
+   "source": [
+    "from sympy import ccode #, cpp_generator\n",
+    "\n",
+    "def generate_code():\n",
+    "\n",
+    "  cpp_code = ccode(dp_dtheta[0], assign_to=\"dx_dtheta\", standard=\"c11\")\n",
+    "\n",
+    "  with open(\"/tmp/expressions.cpp\", \"w\") as f:\n",
+    "    f.write(cpp_code)"
+   ]
+  }
+ ],
+ "metadata": {
+  "kernelspec": {
+   "display_name": "simox_control",
+   "language": "python",
+   "name": "python3"
+  },
+  "language_info": {
+   "codemirror_mode": {
+    "name": "ipython",
+    "version": 3
+   },
+   "file_extension": ".py",
+   "mimetype": "text/x-python",
+   "name": "python",
+   "nbconvert_exporter": "python",
+   "pygments_lexer": "ipython3",
+   "version": "3.7.13"
+  },
+  "orig_nbformat": 4,
+  "vscode": {
+   "interpreter": {
+    "hash": "e4599465d50e71b5ac4fe67b3a4b0cd1869600672e1938bc9720f881263763f9"
+   }
+  }
+ },
+ "nbformat": 4,
+ "nbformat_minor": 2
+}
diff --git a/python/four_bar_mechanism/equations.py b/python/four_bar_mechanism/equations.py
new file mode 100644
index 0000000000000000000000000000000000000000..0f64d68ac46bf68721a784df9d3a8f72cba3cf03
--- /dev/null
+++ b/python/four_bar_mechanism/equations.py
@@ -0,0 +1,38 @@
+import os
+import os.path
+
+from sympy import symbols, sin, cos, sqrt, asin, atan
+
+from hemisphere_joint_demo.sympy_to_code import SympyToCpp
+sp.init_printing(use_latex='mathjax')
+
+# Actuation (P1_z, P2_z)
+
+# active joint
+theta = symbols('theta')
+
+# passive joint
+psi = symbols('psi')
+
+# Constants defining geometry.
+theta0 = symbols('theta0')
+
+shank, p1, p2, p3 = symbols('shank p1 p2 p3')
+
+
+k1 = shank / p1
+k2 = shank / p3
+k3 = (shank**2 + p1**2 + p3**2 - p2**2 ) / (2 * p1 * p3)
+
+cT = cos(theta)
+sT = sin(theta)
+
+A = k1 * cT + k2 + k3 + cT # C.34
+B = -2*sT # C.35
+C = k1 * cT - k2 + k3 - cT # C.36
+
+psi = 2 * atan((-B + sqrt(B * B - 4 * A * C)) / (2 * A)) #  C.39
+
+
+def forwardKinematics(theta):
+  
diff --git a/python/four_bar_mechanism/expressions.cpp b/python/four_bar_mechanism/expressions.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..4bba97d11074f047e06c4742298fbf7977e0c9f4
--- /dev/null
+++ b/python/four_bar_mechanism/expressions.cpp
@@ -0,0 +1,6 @@
+// Not supported in C:
+// ImmutableDenseMatrix
+Matrix([
+[-2*shank*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) + x*(-sin(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))*cos(theta) + 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) - 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))*cos(theta)/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1)) + y*(-sin(theta)*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) - cos(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(theta)*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) + 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*cos(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1))],
+[ -2*shank*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) + x*(sin(theta)*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + cos(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) - 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(theta)*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) - 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*cos(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1)) + y*(-sin(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))*cos(theta) + 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(theta)*cos(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1) - 2*(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))*(2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2))*(8*p1**2*p3**2*sin(theta)*cos(theta) + (-2*p1*p3*sin(theta) - 2*p3*shank*sin(theta))*(-p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank + p2**2 - p3**2 - 2*p3*shank*cos(theta) - shank**2) + (-2*p1*p3*sin(theta) + 2*p3*shank*sin(theta))*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(2*(4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))) + 2*cos(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))*sin(2*atan(p1*p3*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)))*cos(theta)/(p1**2*p3**2*(sqrt((4*p1**2*p3**2*sin(theta)**2 - (p1**2 - 2*p1*p3*cos(theta) - 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)*(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2))/(p1**2*p3**2)) + 2*sin(theta))**2/(p1**2 + 2*p1*p3*cos(theta) + 2*p1*shank - p2**2 + p3**2 + 2*p3*shank*cos(theta) + shank**2)**2 + 1))],
+[                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                                               0]])
\ No newline at end of file