diff --git a/CMakeLists.txt b/CMakeLists.txt
index 9a7e65d679..fa2c9cc03a 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -799,7 +799,8 @@ include_directories("${Simbody_INCLUDE_DIR}")
# CasADi
# ------
if(OPENSIM_WITH_CASADI)
- find_package(casadi 3.4.4 REQUIRED)
+ find_package(casadi 3.4.4 REQUIRED
+ HINTS "${OPENSIM_DEPENDENCIES_DIR}/casadi")
set_package_properties(casadi PROPERTIES
URL https://web.casadi.org
TYPE REQUIRED
@@ -831,7 +832,8 @@ if (OPENSIM_WITH_CASADI OR OPENSIM_WITH_TROPTER)
if(UNIX)
pkg_check_modules(IPOPT REQUIRED ipopt IMPORTED_TARGET)
else()
- find_package(Ipopt REQUIRED CONFIG)
+ find_package(Ipopt REQUIRED CONFIG
+ HINTS "${OPENSIM_DEPENDENCIES_DIR}/ipopt/lib/cmake/Ipopt")
set_package_properties(IPOPT PROPERTIES
URL https://projects.coin-or.org/Ipopt
TYPE REQUIRED
diff --git a/OpenSim/Examples/CMakeLists.txt b/OpenSim/Examples/CMakeLists.txt
index cd62a27839..fdfc011b21 100644
--- a/OpenSim/Examples/CMakeLists.txt
+++ b/OpenSim/Examples/CMakeLists.txt
@@ -24,6 +24,8 @@ if(BUILD_API_EXAMPLES)
add_subdirectory(DataAdapter)
add_subdirectory(Moco)
+ add_subdirectory(TaskSpace)
+
elseif()
add_subdirectory(ControllerExample)
diff --git a/OpenSim/Examples/TaskSpace/CMakeLists.txt b/OpenSim/Examples/TaskSpace/CMakeLists.txt
new file mode 100644
index 0000000000..28d15ac1ad
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/CMakeLists.txt
@@ -0,0 +1,12 @@
+file(TO_CMAKE_PATH "$ENV{OPENSIM_GEOMETRY_DIR}" OPENSIM_GEOMETRY_DIR)
+add_compile_definitions(OPENSIM_GEOMETRY_DIR="${OPENSIM_GEOMETRY_DIR}")
+message(STATUS ${OPENSIM_GEOMETRY_DIR})
+
+#Add all subdirectories
+file(GLOB EXAMPLE_SUBDIRS "*")
+foreach(subdir ${EXAMPLE_SUBDIRS})
+ if(IS_DIRECTORY ${subdir})
+ message("Adding ${subdir}")
+ add_subdirectory(${subdir})
+ endif()
+endforeach()
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/CMakeLists.txt
new file mode 100644
index 0000000000..f617835263
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/CMakeLists.txt
@@ -0,0 +1,23 @@
+
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExampleAbsoluteCoordinates SUBDIR TaskSpace
+ EXECUTABLES ExampleAbsoluteCoordinates
+ RESOURCES "${TEST_FILES}")
+
+# add_executable(ExampleAbsoluteCoordinates ExampleAbsoluteCoordinates.cpp)
+
+# message(STATUS "OpenSim LIBRARIES: ${OpenSim_LIBRARIES}")
+
+# target_link_libraries(ExampleAbsoluteCoordinates PRIVATE osimTaskSpace)
+
+# message(STATUS "OpenSim INCLUDE DIRS: ${OpenSim_INCLUDE_DIRS}")
+
+# target_include_directories(
+# ExampleAbsoluteCoordinates
+# PRIVATE
+# "${CMAKE_SOURCE_DIR}/src"
+# ${OpenSim_INCLUDE_DIRS}
+# "${OpenSim_INCLUDE_DIRS}/OpenSim"
+# ${Simbody_INCLUDE_DIR}
+# "${OpenSim_INCLUDE_DIRS}/../spdlog/include")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/ExampleAbsoluteCoordinates.cpp b/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/ExampleAbsoluteCoordinates.cpp
new file mode 100644
index 0000000000..cd532a2b96
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleAbsoluteCoordinates/ExampleAbsoluteCoordinates.cpp
@@ -0,0 +1,179 @@
+/**
+ * @file ExampleAbsoluteCoordinates.cpp
+ *
+ * \brief This example demonstrating working example of controlling (task space)
+ * a model that is build using absolute (Cartesian) coordinates. Since the
+ * underlying dynamics use constraint projection, constraints are implicitly
+ * accounted.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+Model constructModel(const std::string& name)
+{
+ // model
+ Model model;
+ model.setName(name);
+
+ // construct model
+ auto ground = &model.updGround();
+ // body1
+ double body1_m = 1, body1_length = 1, body1_radius = 0.03;
+ Vec3 body1_com = Vec3(0);
+ Inertia body1_I =
+ body1_m * Inertia::cylinderAlongY(body1_radius, body1_length);
+ auto body1_body = new OpenSim::Body("body1", body1_m, body1_com, body1_I);
+ auto body1_geom = new OpenSim::Cylinder(body1_radius, body1_length / 2);
+ body1_geom->setName("body1_cylinder");
+ body1_body->attachGeometry(body1_geom);
+ Vec3 body1_distal(0, -body1_length / 2, 0);
+ Vec3 body1_proximal(0, body1_length / 2, 0);
+ auto ground_body1 = new OpenSim::FreeJoint("ground_body1", *ground, Vec3(0),
+ Vec3(0), *body1_body, body1_distal, Vec3(0));
+ model.addBody(body1_body);
+ model.addJoint(ground_body1);
+
+ // body2
+ double body2_m = 1, body2_length = 1, body2_radius = 0.03;
+ Vec3 body2_com = Vec3(0);
+ Inertia body2_I =
+ body2_m * Inertia::cylinderAlongY(body2_radius, body2_length);
+ auto body2_body = new OpenSim::Body("body2", body2_m, body2_com, body2_I);
+ auto body2_geom = new OpenSim::Cylinder(body2_radius, body2_length / 2);
+ body2_geom->setName("body2_cylinder");
+ body2_body->attachGeometry(body2_geom);
+ Vec3 body2_distal(0, -body2_length / 2, 0);
+ Vec3 body2_proximal(0, body2_length / 2, 0);
+ auto body1_body2 = new OpenSim::FreeJoint("body1_body2", *body1_body,
+ body1_proximal, Vec3(0), *body2_body, body2_distal, Vec3(0));
+ model.addBody(body2_body);
+ model.addJoint(body1_body2);
+
+ // connect the two free bodies
+ auto pointConstraint1 =
+ new PointConstraint(*ground, Vec3(0), *body1_body, body1_distal);
+ pointConstraint1->setName("pc1");
+ model.addConstraint(pointConstraint1);
+ auto pointConstraint2 = new PointConstraint(
+ *body1_body, body2_proximal, *body2_body, body2_distal);
+ pointConstraint2->setName("pc2");
+ model.addConstraint(pointConstraint2);
+
+ return model;
+}
+
+void setInitialConfiguration(Model& model, const double& q1, const double& q2) {
+ auto* ground_body1 = FreeJoint::safeDownCast(&model.updJointSet().get("ground_body1"));
+ auto* body1_body2 = FreeJoint::safeDownCast(&model.updJointSet().get("body1_body2"));
+
+ auto& state = model.updWorkingState();
+
+ // initial configuration (pose)
+ ground_body1->upd_coordinates(2).setValue(
+ state, convertDegreesToRadians(q1));
+ body1_body2->upd_coordinates(2).setValue(
+ state, convertDegreesToRadians(q2));
+}
+
+void absoluteCoordinates() {
+ // parameters
+ const double q1 = -45.0;
+ const double q2 = 90;
+ const string taskBodyName = "body2";
+ const string example = "ExampleAbsoluteCoordinates";
+
+ auto model = constructModel(example);
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(DeSapioModel());
+ controller->set_control_strategy("force");
+ // model takes ownership
+ model.addController(controller);
+
+ // build and initialize model
+ model.setUseVisualizer(false);
+ model.initSystem();
+
+ setInitialConfiguration(model, q1, q2);
+
+ auto& taskBody = model.updBodySet().get(taskBodyName);
+ auto point = SimTK::Vec3(0, 0.5, 0);
+ auto& state = model.updWorkingState();
+ Vec3 initialPosition = taskBody.findStationLocationInGround(state, point);
+
+ // Set up position tracking for the block
+ auto task = new StationTask();
+ task->setName(taskBodyName+"task");
+ task->set_priority(0);
+ task->set_point(point);
+
+ task->set_kp(Array(100, 3));
+ task->set_kv(Array(20, 3));
+ task->set_weight(Array(1,3));
+
+ auto x_desired = Constant(initialPosition[0]);
+ auto y_desired = Sine(0.2, 2 * Pi, 0, initialPosition[1]);
+ auto z_desired = Constant(initialPosition[2]);
+
+ task->set_position_functions(0, x_desired);
+ task->set_position_functions(1, y_desired);
+ task->set_position_functions(2, z_desired);
+ task->set_wrt_body(taskBodyName);
+
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(task);
+
+ // reinitialize to set up the task
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+
+ //reapply the initial configuration
+ setInitialConfiguration(model, q1, q2);
+
+ // configure visualizer
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(true);
+ }
+
+ // simulate
+ simulate(model, state, 2, true);
+
+ // export results
+ IO::makeDir("results");
+ controller->printResults(example, IO::getCwd()+"/results");
+ bodyKinematics->printResults(example, IO::getCwd()+"/results");
+
+ model.print(IO::getCwd()+"/results/"+example+".osim");
+}
+
+int main(int argc, char* argv[]) {
+ Logger::setLevel(Logger::Level::Info);
+ try {
+ absoluteCoordinates();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ return -1;
+ }
+ cout << "Example absolute coordinates finished." << endl;
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleArm26/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleArm26/CMakeLists.txt
new file mode 100644
index 0000000000..b18252108a
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleArm26/CMakeLists.txt
@@ -0,0 +1,5 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExampleArm26 SUBDIR TaskSpace
+ EXECUTABLES ExampleArm26
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleArm26/ExampleArm26.cpp b/OpenSim/Examples/TaskSpace/ExampleArm26/ExampleArm26.cpp
new file mode 100644
index 0000000000..a238b3876f
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleArm26/ExampleArm26.cpp
@@ -0,0 +1,144 @@
+/**
+ * @file ExampleArm26.cpp
+ *
+ * \brief This example demonstrates multi-tasking control of a musculoskeletal
+ * system. Two tasks are used in prioritized scheme and an optimization is
+ * performed for mapping the task space generalized forces to muscle
+ * excitations.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+Vec3 fromVectorToVec3(const Vector& v) { return Vec3(v[0], v[1], v[2]); }
+
+void arm26Simulation() {
+ const string example = "ExampleArm26";
+
+ ModelVisualizer::addDirToGeometrySearchPaths(OPENSIM_GEOMETRY_DIR);
+
+ const int kp = 100;
+ const int kv = 20;
+
+ // load model
+ Model model("arm26.osim");
+ model.setName(example);
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(NoConstraintModel());
+ controller->set_control_strategy("force");
+ model.addController(controller);
+
+ // build and initialize model so we can retrieve its initial configuration
+ auto& state = model.initSystem();
+ model.realizePosition(state);
+
+ double initial_shoulder_elevation = 0.1;
+ model.updCoordinateSet()
+ .get("r_shoulder_elev")
+ .setValue(state, initial_shoulder_elevation);
+
+ // humerus initial configuration
+ auto& humerusBody = model.updBodySet().get("r_humerus");
+ Vec3 initialOrientation_hum = humerusBody.getRotationInGround(state)
+ .convertRotationToBodyFixedXYZ();
+
+ // Set up orientation tracking for the humerus
+ auto humerusTask = new OrientationTask();
+ humerusTask->setName("r_humerus");
+ humerusTask->set_priority(0);
+
+ humerusTask->set_kp(Array(kp, 3));
+ humerusTask->set_kv(Array(kv, 3));
+ humerusTask->set_weight(Array(1.0, 3));
+
+ auto x_desired_hum = Constant(initialOrientation_hum[0]);
+ auto y_desired_hum = Constant(initialOrientation_hum[1]);
+ auto z_desired_hum = Constant(initialOrientation_hum[2]);
+
+ humerusTask->set_position_functions(0, x_desired_hum);
+ humerusTask->set_position_functions(1, y_desired_hum);
+ humerusTask->set_position_functions(2, z_desired_hum);
+ humerusTask->set_wrt_body("r_humerus");
+
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(humerusTask);
+
+ // ulna initial configuration
+ auto& ulnaBody = model.getBodySet().get("r_ulna_radius_hand");
+ Vec3 initialOrientation_uln =
+ ulnaBody.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+
+ // Set up orientation tracking for the ulna
+ auto ulnaTask = new OrientationTask();
+ ulnaTask->setName("r_ulna_radius_hand");
+ ulnaTask->set_priority(0);
+
+ ulnaTask->set_kp(Array(kp, 3));
+ ulnaTask->set_kv(Array(kv, 3));
+ humerusTask->set_weight(Array(1.0, 3));
+
+ auto x_desired_uln = Constant(0.0);
+ auto y_desired_uln = Constant(0.0);
+ auto z_desired_uln =
+ Sine(Pi / 4.0, 1 * Pi, 0, initialOrientation_uln[2] + 1);
+
+ ulnaTask->set_position_functions(0, x_desired_uln);
+ ulnaTask->set_position_functions(1, y_desired_uln);
+ ulnaTask->set_position_functions(2, z_desired_uln);
+ ulnaTask->set_wrt_body("r_ulna_radius_hand");
+ ulnaTask->set_express_body("ground");
+
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(ulnaTask);
+
+ // build and initialize model to initialize the tasks. also add a visualizer
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+ model.updCoordinateSet()
+ .get("r_shoulder_elev")
+ .setValue(state, initial_shoulder_elevation);
+
+ // configure visualizer
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(false);
+ }
+
+ // print the complete model
+ model.print(example + ".osim");
+
+ // simulate
+ simulate(model, state, 4.0, true);
+
+ // export results
+ controller->printResults(example, ".");
+ bodyKinematics->printResults(example, ".");
+}
+
+int main(int argc, char* argv[]) {
+ try {
+ arm26Simulation();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ // getchar();
+ return -1;
+ }
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleArm26/arm26.osim b/OpenSim/Examples/TaskSpace/ExampleArm26/arm26.osim
new file mode 100644
index 0000000000..6fb32ab12d
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleArm26/arm26.osim
@@ -0,0 +1,1647 @@
+
+
+
+
+
+ The OpenSim Development Team (Reinbolt, J; Seth, A; Habib, A; Hamner, S) adapted from a model originally created by Kate Holzbaur (11/22/04)
+
+ License:
+ Creative Commons (CCBY 3.0). You are free to distribute, remix, tweak, and build upon this work, even commercially,
+ as long as you credit us for the original creation.
+ http://creativecommons.org/licenses/by/3.0/
+
+ Holzbaur, K.R.S., Murray, W.M., Delp, S.L. A Model of the Upper Extremity for Simulating Musculoskeletal Surgery and Analyzing Neuromuscular Control.
+ Annals of Biomedical Engineering, vol 33, pp 829–840, 2005
+ meters
+ N
+
+ 0 -9.8066 0
+
+
+
+
+ 0
+ 0 0 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+
+
+
+ 0
+ 0 0 0
+ 0
+ 0
+ 0
+ 0
+ 0
+ 0
+
+
+
+
+ ground
+
+ 0 0.8 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ ground_ribs.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ ground_spine.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ ground_skull.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ ground_jaw.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ ground_r_clavicle.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ ground_r_scapula.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ 1.37532 -0.294612 2.43596
+ -0.043905 -0.0039 0.1478
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.37532 -0.294612 2.43596 -0.043905 -0.0039 0.1478
+
+ false
+
+ 4
+
+ 0.003
+ 0.03
+
+
+
+
+
+
+ 1.864572
+ 0 -0.180496 0
+ 0.01481
+ 0.004551
+ 0.013193
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ r_shoulder_elev
+
+ -0.05889802 0.0023 0.99826136
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.99826136 -0 0.05889802
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+ base
+ -0.017545 -0.007 0.17
+ 0 0 0
+ 0 0 0
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.57079633 3.14159265
+
+ false
+
+ false
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ arm_r_humerus.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ 3.00162 -0.853466 2.57419
+ -0.0078 -0.0041 -0.0014
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 3.00162 -0.853466 2.57419 -0.0078 -0.0041 -0.0014
+
+ false
+
+ 4
+
+ 0.035 0.02 0.02
+
+
+ -2.00434 -1.00164 0.975465
+ 0.0033 0.0073 0.0003
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -2.00434 -1.00164 0.975465 0.0033 0.0073 0.0003
+
+ false
+
+ 4
+
+ 0.025 0.02 0.02
+
+
+ -0.14015 -0.00628319 0.154985
+ 0.0028 -0.2919 -0.0069
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.14015 -0.00628319 0.154985 0.0028 -0.2919 -0.0069
+
+ false
+
+ 4
+
+ 0.016
+ 0.05
+
+
+
+
+
+
+ 1.534315
+ 0 -0.181479 0
+ 0.019281
+ 0.001571
+ 0.020062
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ r_elbow_flex
+
+ 0.04940001 0.03660001 0.99810825
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.99810825 0 -0.04940001
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+ r_humerus
+ 0.0061 -0.2904 -0.0123
+ 0 0 0
+ 0 0 0
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ 0 2.26892803
+
+ false
+
+ false
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ arm_r_ulna.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_radius.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_lunate.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_scaphoid.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_pisiform.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_triquetrum.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_capitate.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_trapezium.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_trapezoid.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_hamate.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_1mc.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_2mc.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_3mc.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_4mc.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_5mc.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_thumbprox.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_thumbdist.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_2proxph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_2midph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_2distph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_3proxph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_3midph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_3distph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_4proxph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_4midph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_4distph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_5proxph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_5midph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ arm_r_5distph.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ -0.05365 -0.01373 0.14723
+ base
+
+
+ -0.02714 -0.11441 -0.00664
+ r_humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ r_humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ r_humerus
+
+
+ -0.0219 0.01046 -0.00078
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+ TRIlonghh
+ hybrid
+ -1 -1
+
+
+ TRIlongglen
+ hybrid
+ -1 -1
+
+
+
+
+
+
+ 1
+
+ 798.52
+
+ 0.134
+
+ 0.143
+
+ 0.20943951
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ -0.00599 -0.12646 0.00428
+ r_humerus
+
+
+ -0.02344 -0.14528 0.00928
+ r_humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ r_humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ r_humerus
+
+
+ -0.0219 0.01046 -0.00078
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+ 1
+
+ 624.3
+
+ 0.1138
+
+ 0.098
+
+ 0.15707963
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ -0.00838 -0.13695 -0.00906
+ r_humerus
+
+
+ -0.02601 -0.15139 -0.0108
+ r_humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ r_humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ r_humerus
+
+
+ -0.0219 0.01046 -0.00078
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+ 1
+
+ 624.3
+
+ 0.1138
+
+ 0.0908
+
+ 0.15707963
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ -0.039235 0.00347 0.14795
+ base
+
+
+ -0.028945 0.01391 0.15639
+ base
+
+
+ 0.02131 0.01793 0.01028
+ r_humerus
+
+
+ 0.02378 -0.00511 0.01201
+ r_humerus
+
+
+ 0.01345 -0.02827 0.00136
+ r_humerus
+
+
+ 0.01068 -0.07736 -0.00165
+ r_humerus
+
+
+ 0.01703 -0.12125 0.00024
+ r_humerus
+
+
+ 0.0228 -0.1754 -0.0063
+ r_humerus
+
+
+ 0.00751 -0.04839 0.02179
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ BIClonghh
+ hybrid
+ 2 3
+
+
+
+
+
+
+ 1
+
+ 624.3
+
+ 0.1157
+
+ 0.2723
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ 0.004675 -0.01231 0.13475
+ base
+
+
+ -0.007075 -0.04004 0.14507
+ base
+
+
+ 0.01117 -0.07576 -0.01101
+ r_humerus
+
+
+ 0.01703 -0.12125 -0.01079
+ r_humerus
+
+
+ 0.0228 -0.1754 -0.0063
+ r_humerus
+
+
+ 0.00751 -0.04839 0.02179
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1
+
+ 435.56
+
+ 0.1321
+
+ 0.1923
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+ 0.0068 -0.1739 -0.0036
+ r_humerus
+
+
+ -0.0032 -0.0239 0.0009
+ r_ulna_radius_hand
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+ 1
+
+ 987.26
+
+ 0.0858
+
+ 0.0535
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+
+
+
+
+
+
+ base
+
+ -0.01256 0.04 0.17
+
+ false
+
+
+
+ r_humerus
+
+ 0.005 -0.2904 0.03
+
+ false
+
+
+
+ r_ulna_radius_hand
+
+ -0.0011 -0.23559 0.0943
+
+ false
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/CMakeLists.txt
new file mode 100644
index 0000000000..e1d0d68eaf
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/CMakeLists.txt
@@ -0,0 +1,5 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExampleClosedKinematicChain SUBDIR TaskSpace
+ EXECUTABLES ExampleClosedKinematicChain
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/ExampleClosedKinematicChain.cpp b/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/ExampleClosedKinematicChain.cpp
new file mode 100644
index 0000000000..7cededdee9
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleClosedKinematicChain/ExampleClosedKinematicChain.cpp
@@ -0,0 +1,183 @@
+/**
+ * @file ExampleClosedKinematicChain.cpp
+ *
+ * \brief This example demonstrating working example of controlling (task
+ * space) a model of a closed kinematic chain topology that is build using
+ * absolute (Cartesian) coordinates. Since the underlying dynamics use
+ * constraint projection, constraints are implicitly accounted.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+Vec3 fromVectorToVec3(const Vector& v) { return Vec3(v[0], v[1], v[2]); }
+
+void closedKinematicChain() {
+ // parameters
+ string taskBodyName = "body1";
+ const double q1 = -0.0;
+ double body3_length = 1;
+ const string example = "ExampleClosedKinematicChain";
+
+ // create model
+ Model model;
+ model.setName(example);
+ auto& ground = model.getGround();
+
+ // construct body-joints
+ // body1
+ double body1_m = 1, body1_length = 1, body1_radius = 0.03;
+ Vec3 body1_com = Vec3(0);
+ Inertia body1_I =
+ body1_m * Inertia::cylinderAlongY(body1_radius, body1_length);
+ auto body1_body = new OpenSim::Body("body1", body1_m, body1_com, body1_I);
+ auto body1_geom = new OpenSim::Cylinder(body1_radius, body1_length / 2);
+ body1_geom->setName("body1_cylinder");
+ body1_body->attachGeometry(body1_geom);
+ Vec3 body1_distal(0, -body1_length / 2, 0);
+ Vec3 body1_proximal(0, body1_length / 2, 0);
+ auto ground_body1 = new OpenSim::PinJoint("ground_body1", ground, Vec3(0),
+ Vec3(0), *body1_body, body1_distal, Vec3(0));
+ ground_body1->upd_coordinates(0).setDefaultValue(
+ SimTK::convertDegreesToRadians(q1));
+ model.addBody(body1_body);
+ model.addJoint(ground_body1);
+
+ // body2
+ double body2_m = 1, body2_length = 1, body2_radius = 0.03;
+ Vec3 body2_com = Vec3(0);
+ Inertia body2_I =
+ body2_m * Inertia::cylinderAlongY(body2_radius, body2_length);
+ auto body2_body = new OpenSim::Body("body2", body2_m, body2_com, body2_I);
+ auto body2_geom = new OpenSim::Cylinder(body2_radius, body2_length / 2);
+ body2_geom->setName("body2_cylinder");
+ body2_body->attachGeometry(body2_geom);
+ Vec3 body2_distal(0, -body2_length / 2, 0);
+ Vec3 body2_proximal(0, body2_length / 2, 0);
+ auto ground_body2 = new OpenSim::PinJoint("body1_body2", ground,
+ Vec3(body3_length, 0, 0), Vec3(0), *body2_body, body2_distal,
+ Vec3(0));
+ ground_body2->upd_coordinates(0).setDefaultValue(
+ SimTK::convertDegreesToRadians(q1));
+ model.addBody(body2_body);
+ model.addJoint(ground_body2);
+
+ // body3
+ double body3_m = 1, body3_radius = 0.03;
+ Vec3 body3_com = Vec3(0);
+ Inertia body3_I =
+ body3_m * Inertia::cylinderAlongY(body3_radius, body3_length);
+ auto body3_body = new OpenSim::Body("body3", body3_m, body3_com, body3_I);
+ auto body3_geom = new OpenSim::Cylinder(body3_radius, body3_length / 2);
+ body3_geom->setName("body3_cylinder");
+ body3_body->attachGeometry(body3_geom);
+ Vec3 body3_distal(0, -body3_length / 2, 0);
+ Vec3 body3_proximal(0, body3_length / 2, 0);
+ auto ground_body3 = new OpenSim::FreeJoint("body1_body3", ground, Vec3(0),
+ Vec3(0), *body3_body, body3_distal, Vec3(0));
+ model.addBody(body3_body);
+ model.addJoint(ground_body3);
+
+ // connect the two free bodies with constraints
+ auto pointConstraint1 = new PointConstraint(
+ *body1_body, body1_proximal, *body3_body, body3_distal);
+ pointConstraint1->setName("pc1");
+ model.addConstraint(pointConstraint1);
+ auto pointConstraint2 = new PointConstraint(
+ *body2_body, body2_proximal, *body3_body, body3_proximal);
+ pointConstraint2->setName("pc2");
+ model.addConstraint(pointConstraint2);
+
+ auto& state = model.initSystem();
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(AghiliModel());
+ controller->set_control_strategy("force");
+ model.addController(controller);
+
+ // build and initialize model
+ state = model.initSystem();
+
+ // initial configuration (pose)
+ model.updCoordinateSet()[0].setValue(state, convertDegreesToRadians(q1));
+ model.updCoordinateSet()[1].setValue(state, convertDegreesToRadians(q1));
+ auto& taskBody = model.updBodySet().get(taskBodyName);
+ Vec3 initialOrientation =
+ taskBody.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+
+ // Set up orientation tracking
+ auto task = new OrientationTask();
+ task->setName(taskBodyName);
+ task->set_priority(0);
+
+ task->set_kp(Array(100, 3));
+ task->set_kv(Array(20, 3));
+ task->set_weight(Array(1, 3));
+
+ task->set_direction_vectors(0, SimTK::Vec3(1, 0, 0));
+ task->set_direction_vectors(1, SimTK::Vec3(0, 1, 0));
+ task->set_direction_vectors(2, SimTK::Vec3(0, 0, 1));
+ // task->set_active(Array(true));
+ auto x_desired = Constant(initialOrientation[0]);
+ auto y_desired = Constant(initialOrientation[1]);
+ auto z_desired = Sine(0.9*Pi / 2, 2 * Pi, 0, initialOrientation[2]);
+
+ task->set_position_functions(0, x_desired);
+ task->set_position_functions(1, y_desired);
+ task->set_position_functions(2, z_desired);
+
+ task->set_wrt_body(taskBodyName);
+
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(task);
+
+ // build and initialize model to initialize the tasks. also add a visualizer
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+
+ // configure visualizer
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(true);
+ }
+
+ // simulate
+ simulate(model, state, 2, true);
+
+ // export results
+ controller->printResults(example, "/results");
+ bodyKinematics->printResults(example, "/results");
+
+ model.print("ExampleClosedKinematicChain.osim");
+}
+
+int main(int argc, char* argv[]) {
+ Logger::setLevel(Logger::Level::Info);
+
+ try {
+ closedKinematicChain();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ // getchar();
+ return -1;
+ }
+ cout << "done" << endl;
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleCycling/CMakeLists.txt
new file mode 100644
index 0000000000..5ecbecc46d
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/CMakeLists.txt
@@ -0,0 +1,7 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim *.obj)
+
+message(STATUS ${TEST_FILES})
+
+OpenSimAddExampleCXX(NAME ExampleCycling SUBDIR TaskSpace
+ EXECUTABLES ExampleCycling
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/ExampleCycling.cpp b/OpenSim/Examples/TaskSpace/ExampleCycling/ExampleCycling.cpp
new file mode 100644
index 0000000000..59bc03d4da
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/ExampleCycling.cpp
@@ -0,0 +1,175 @@
+/**
+ * @file ExampleCycling.cpp
+ *
+ * \brief Simulation of cycling using task space control of the gear rotation.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+#define USE_VISUALIZER 1
+
+Vec3 fromVectorToVec3(const Vector& v) { return Vec3(v[0], v[1], v[2]); }
+
+SimTK::State simulate2(Model& model, const SimTK::State& initialState,
+ double finalTime, bool saveStatesFile = false) {
+ // Returned/ state begins as a copy of the initial state
+ SimTK::State state = initialState;
+ SimTK::Visualizer::InputSilo* silo;
+
+ bool simulateOnce = true;
+
+ // Configure the visualizer.
+ if (model.getUseVisualizer() && model.hasVisualizer()) {
+ SimTK::Visualizer& viz = model.updVisualizer().updSimbodyVisualizer();
+ // We use the input silo to get key presses.
+ silo = &model.updVisualizer().updInputSilo();
+
+ SimTK::DecorativeText help("Press any key to start a new simulation; "
+ "ESC to quit.");
+ help.setIsScreenText(true);
+ viz.addDecoration(SimTK::MobilizedBodyIndex(0), SimTK::Vec3(0), help);
+
+ viz.setShowSimTime(true);
+ viz.drawFrameNow(state);
+ std::cout << "A visualizer window has opened." << std::endl;
+
+ // if visualizing enable replay
+ simulateOnce = false;
+ }
+
+ // Simulate until the user presses ESC (or enters 'q' if visualization has
+ // been disabled).
+ do {
+ if (model.getUseVisualizer() && model.hasVisualizer()) {
+ // Get a key press.
+ silo->clear(); // Ignore any previous key presses.
+ unsigned key, modifiers;
+ silo->waitForKeyHit(key, modifiers);
+ if (key == SimTK::Visualizer::InputListener::KeyEsc) { break; }
+ }
+
+ // reset the state to the initial state
+ state = initialState;
+ // Set up manager and simulate.
+ Manager manager(model);
+ state.setTime(0.0);
+ manager.setIntegratorAccuracy(
+ 1e-1); // model is a bit unstable due to constraints
+ manager.initialize(state);
+ manager.integrate(finalTime);
+
+ // Save the states to a storage file (if requested).
+ if (saveStatesFile) {
+ manager.getStateStorage().print(model.getName() + "_states.sto");
+ }
+ } while (!simulateOnce);
+
+ return state;
+}
+
+void cyclingSimulation() {
+ const string example = "ExampleCycling";
+
+ ModelVisualizer::addDirToGeometrySearchPaths(OPENSIM_GEOMETRY_DIR);
+
+ // load model
+ Model model("bicycle_v10.osim");
+ model.set_assembly_accuracy(0.1);
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(NoConstraintModel());
+ model.addController(controller);
+
+ // disable any actuators when computing the total force to improve
+ // simulation time
+ auto& ms = model.updMuscles();
+ for (int i = 0; i < ms.getSize(); i++) { ms[i].set_appliesForce(false); }
+
+ // build and initialize model
+ model.finalizeFromProperties();
+ auto& state = model.initSystem();
+
+ // gears initial configuration
+ auto& gearsBody = model.updBodySet().get("gears");
+ Vec3 initialOrientation = gearsBody.getRotationInGround(state)
+ .convertRotationToBodyFixedXYZ();
+
+ Vec3 direction(1.0, 0.0, 0.0);
+ double mag = 2 * Pi;
+
+ // Set up orientation tracking for the humerus
+ auto gearsTask = new OrientationTask();
+ gearsTask->setName("gears_task");
+
+ gearsTask->set_kp(Array(500, 3));
+ gearsTask->set_kv(Array(50, 3));
+
+ gearsTask->set_direction_vectors(0, SimTK::Vec3(1, 0, 0));
+ gearsTask->set_direction_vectors(1, SimTK::Vec3(0, 1, 0));
+ gearsTask->set_direction_vectors(2, SimTK::Vec3(0, 0, 1));
+
+ auto x_desired = LinearFunction(mag * direction[0], initialOrientation[0]);
+ auto y_desired = LinearFunction(mag * direction[1], initialOrientation[1]);
+ auto z_desired = LinearFunction(mag * direction[2], initialOrientation[2]);
+
+ gearsTask->set_position_functions(0, x_desired);
+ gearsTask->set_position_functions(1, y_desired);
+ gearsTask->set_position_functions(2, z_desired);
+ gearsTask->set_wrt_body("gears");
+
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(gearsTask);
+
+#if USE_VISUALIZER == 1
+ model.setUseVisualizer(true);
+#endif
+ model.initSystem();
+
+ // configure visualizer
+#if USE_VISUALIZER == 1
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(false);
+ }
+#endif
+
+ // print the complete model
+ model.print(example + ".osim");
+
+ // simulate we have to relax the tolerance because of the constraints
+ // simulate(model, state, 2, true);
+ simulate2(model, state, 4.0, true);
+
+ // export results
+ controller->printResults(example, ".");
+ bodyKinematics->printResults(example, ".");
+}
+
+int main(int argc, char* argv[]) {
+ try {
+ cyclingSimulation();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ getchar();
+ return -1;
+ }
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/bicycle_v10.osim b/OpenSim/Examples/TaskSpace/ExampleCycling/bicycle_v10.osim
new file mode 100644
index 0000000000..85cbbe21aa
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/bicycle_v10.osim
@@ -0,0 +1,6595 @@
+
+
+
+ Dimitris Boulgarakis, Dimitar Stanev, Konstantinos Moustakas
+ Unassigned
+ meters
+ N
+
+ 0 -9.80665 0
+
+
+
+
+ 0
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 10
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ ground
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ geometry/frame.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.3
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ frame
+
+ 0.00114552 0.376431 -0.399321
+
+ 0 0 0
+
+ 0 0 0
+
+ 0.2 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ geometry/saddle.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.5
+ 0.02 0 0
+ 0.0074390625
+ 0.001
+ 0.001
+ 0
+ 0
+ 0
+
+
+
+
+ frame
+
+ -0.0266384 -0.291526 -0.20305
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.290844098162084
+
+ 0
+
+ -3.14 3.14
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ gear_rotation
+
+ 1 0 0
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ geometry/gears.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.15
+ 0 0 0
+ 6.75e-005
+ 1e-005
+ 1e-005
+ 0
+ 0
+ 0
+
+
+
+
+ gears
+
+ 0.1187419 -0.113054 0.159427
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.165246359379097
+
+ 0
+
+ -3.14 3.14
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ pedal_rotation_l
+
+ 1 0 0
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ geometry/pedal_l.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.15
+ 0 0 0
+ 6.75e-005
+ 1e-005
+ 1e-005
+ 0
+ 0
+ 0
+
+
+
+
+ gears
+
+ -0.0810048 0.109176 -0.179171
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.623148478136415
+
+ 0
+
+ -3.14 3.14
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ pedal_rotation_r
+
+ 1 0 0
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ geometry/pedal_r.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.5
+ 0 0 0
+ 0.063948
+ 0.01
+ 0.01
+ 0
+ 0
+ 0
+
+
+
+
+ frame
+
+ 0.00640082 -0.245379 -0.685729
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ geometry/wheel_r.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.5
+ 0 0 0
+ 0.063948
+ 0.01
+ 0.01
+ 0
+ 0
+ 0
+
+
+
+
+ frame
+
+ 0.00274065 -0.23821 0.505443
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ geometry/wheel_f.obj
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 0.5 0.5 0.5
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 10.75379227
+ -0.0739512 0 0
+ 0.1027003
+ 0.08701554
+ 0.05784385
+ 0
+ 0
+ 0
+
+
+
+
+ saddle
+
+ 0 0.1722512 0.0434398
+
+ -0.18 4.68 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ sacrum.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ pelvis.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ l_pelvis.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.04599 1.04599 1.04599
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 8.54926632
+ 0 -0.199543 0
+ 0.16956431
+ 0.0444489
+ 0.17880867
+ 0
+ 0
+ 0
+
+
+
+
+ pelvis
+
+ -0.0707 -0.0661 0.0835
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.758505837753148
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0173469247843802
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0302796770213648
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ hip_flexion_r
+
+ 0 0 1
+
+
+
+ 1 0
+
+
+
+
+
+ hip_adduction_r
+
+ 1 0 0
+
+
+
+ 1 0
+
+
+
+
+
+ hip_rotation_r
+
+ 0 1 0
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ femur_r.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.17378 1.17378 1.17378
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 4.67404243
+ 0 -0.2098 0
+ 0.08023514
+ 0.00811903
+ 0.08134951
+ 0
+ 0
+ 0
+
+
+
+
+ femur_r
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -2.05677147509942
+
+ 0
+
+ -2.0943951 0.17453293
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ knee_angle_r
+
+ 0 0 1
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+ knee_angle_r
+
+ 1 0 0
+
+
+
+
+
+ -2.0944 -1.74533 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0.197344 0.337395 0.490178 1.52146 2.0944
+ -0.0037561 0.00210107 0.00482424 0.00481249 0.00248841 -0.00117378 -0.00363871 -0.00613534 -0.00637949 -0.00654265 -0.00637949 -0.00616234
+
+
+ 1
+
+
+
+
+
+ knee_angle_r
+
+ 0 1 0
+
+
+
+
+
+ -2.0944 -1.22173 -0.523599 -0.349066 -0.174533 0.159149 2.0944
+ -0.496039 -0.479137 -0.468338 -0.466695 -0.465521 -0.463953 -0.464817
+
+
+ 1
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+
+
+ 0
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+ tibia_r.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ fibula_r.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.12373 1.12373 1.12373
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.09191376
+ 0 0 0
+ 0.00110296
+ 0.00110296
+ 0.00110296
+ 0
+ 0
+ 0
+
+
+
+
+ tibia_r
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -2.05677131619951
+
+ 0
+
+ -2.094 10
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ knee_angle_pat_r
+
+ 0 0 1
+
+
+
+ -2.0944 -1.99997 -1.45752 -0.526391 0.0279253 0.174533
+ 0.308051 0.308051 0.306305 0.270177 -0.037001 -0.279951
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+ knee_angle_pat_r
+
+ 1 0 0
+
+
+
+
+
+ -2.0944 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0872665 2.0944
+ 0.0194405 0.0364088 0.042814 0.0483203 0.0527029 0.0543884 0.0557369 0.0557369 0.0557369 0.0557369 0.0557369
+
+
+ 1
+
+
+
+
+
+ knee_angle_pat_r
+
+ 0 1 0
+
+
+
+
+
+ -2.0944 -1.5708 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0872665 2.0944
+ -0.0246096 -0.0226993 -0.0224746 -0.0229241 -0.0237107 -0.0246096 -0.0250591 -0.0255086 -0.0255086 -0.0255086 -0.0255086 -0.0255086
+
+
+ 1
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+
+
+ 0
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+ pat.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.09544 1.09544 1.09544
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.12606858
+ 0 0 0
+ 0.00202166
+ 0.00202166
+ 0.00202166
+ 0
+ 0
+ 0
+
+
+
+
+ tibia_r
+
+ 0 -0.483203 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ talus.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.26634 1.26634 1.26634
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.07224816
+ 0.102693 0.0308079 0
+ 0.00090462
+ 0.00361848
+ 0.00361848
+ 0
+ 0
+ 0
+
+
+
+
+ talus_r
+
+ -0.0620508 -0.0531864 0.0101307
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ foot.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.02693 1.02693 1.02693
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.18614228
+ 0.0359425 0.00616157 -0.0184847
+ 0
+ 0
+ 0.00090462
+ 0
+ 0
+ 0
+
+
+
+
+ calcn_r
+
+ 0.18382 -0.00205386 0.00102692
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ bofoot.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.02693 1.02693 1.02693
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 8.54926632
+ 0 -0.199543 0
+ 0.16956431
+ 0.0444489
+ 0.17880867
+ 0
+ 0
+ 0
+
+
+
+
+ pelvis
+
+ -0.0707 -0.0661 -0.0835
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.283108277296816
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ -0.0058223051100806
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ -0.0312718647970803
+
+ 0
+
+ -2.0943951 2.0943951
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ hip_flexion_l
+
+ 0 0 1
+
+
+
+ 1 0
+
+
+
+
+
+ hip_adduction_l
+
+ -1 0 0
+
+
+
+ 1 0
+
+
+
+
+
+ hip_rotation_l
+
+ 0 -1 0
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ femur_l.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.17378 1.17378 1.17378
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 4.67404243
+ 0 -0.2098 0
+ 0.08023514
+ 0.00811903
+ 0.08134951
+ 0
+ 0
+ 0
+
+
+
+
+ femur_l
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.787801070912712
+
+ 0
+
+ -2.0943951 0.17453293
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ knee_angle_l
+
+ 0 0 1
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+ knee_angle_l
+
+ 1 0 0
+
+
+
+
+
+ -2.0944 -1.74533 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0.197344 0.337395 0.490178 1.52146 2.0944
+ -0.0037561 0.00210107 0.00482424 0.00481249 0.00248841 -0.00117378 -0.00363871 -0.00613534 -0.00637949 -0.00654265 -0.00637949 -0.00616234
+
+
+ 1
+
+
+
+
+
+ knee_angle_l
+
+ 0 1 0
+
+
+
+
+
+ -2.0944 -1.22173 -0.523599 -0.349066 -0.174533 0.159149 2.0944
+ -0.496039 -0.479137 -0.468338 -0.466695 -0.465521 -0.463953 -0.464817
+
+
+ 1
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+
+
+ 0
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+ tibia_l.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ fibula_l.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.12373 1.12373 1.12373
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.09191376
+ 0 0 0
+ 0.00110296
+ 0.00110296
+ 0.00110296
+ 0
+ 0
+ 0
+
+
+
+
+ tibia_l
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.787801088830655
+
+ 0
+
+ -2.094 10
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ knee_angle_pat_l
+
+ 0 0 1
+
+
+
+ -2.0944 -1.99997 -1.45752 -0.526391 0.0279253 0.174533
+ 0.308051 0.308051 0.306305 0.270177 -0.037001 -0.279951
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+ knee_angle_pat_l
+
+ 1 0 0
+
+
+
+
+
+ -2.0944 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0872665 2.0944
+ 0.0194405 0.0364088 0.042814 0.0483203 0.0527029 0.0543884 0.0557369 0.0557369 0.0557369 0.0557369 0.0557369
+
+
+ 1
+
+
+
+
+
+ knee_angle_pat_l
+
+ 0 1 0
+
+
+
+
+
+ -2.0944 -1.5708 -1.39626 -1.0472 -0.698132 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0872665 2.0944
+ -0.0246096 -0.0226993 -0.0224746 -0.0229241 -0.0237107 -0.0246096 -0.0250591 -0.0255086 -0.0255086 -0.0255086 -0.0255086 -0.0255086
+
+
+ 1
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+
+
+ 0
+
+
+ 1
+
+
+
+
+
+
+
+
+
+
+
+
+ pat.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.09544 1.09544 1.09544
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.12606858
+ 0 0 0
+ 0.00202166
+ 0.00202166
+ 0.00202166
+ 0
+ 0
+ 0
+
+
+
+
+ tibia_l
+
+ 0 -0.483203 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ talus.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.26634 1.26634 1.26634
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.07224816
+ 0.102693 0.0308079 0
+ 0.00090462
+ 0.00361848
+ 0.00361848
+ 0
+ 0
+ 0
+
+
+
+
+ talus_l
+
+ -0.0620508 -0.0531864 -0.0101307
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ l_foot.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.02693 1.02693 1.02693
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.18614228
+ 0.0359425 0.00616157 0.0184847
+ 0
+ 0
+ 0.00090462
+ 0
+ 0
+ 0
+
+
+
+
+ calcn_l
+
+ 0.18382 -0.00205386 -0.00102692
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+
+ false
+
+
+
+
+
+
+
+
+ l_bofoot.vtp
+
+ 1 1 1
+
+
+
+ -0 0 -0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1.02693 1.02693 1.02693
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+
+
+ 1 0
+
+
+
+ knee_angle_r
+
+ knee_angle_pat_r
+
+ 1
+
+
+
+ false
+
+
+
+ 1 0
+
+
+
+ knee_angle_l
+
+ knee_angle_pat_l
+
+ 1
+
+
+
+ false
+
+ toes_r
+
+ pedal_r
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 1.57 0
+
+
+
+ false
+
+ toes_l
+
+ pedal_l
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 1.57 0
+
+
+
+
+
+
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0408 0.0304 0.1209
+ pelvis
+
+
+ -0.0218 -0.0117 0.0555
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1119
+
+ 0.0535
+
+ 0.078
+
+ 0.13962634
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0855 0.0445 0.0766
+ pelvis
+
+
+ -0.0258 -0.0058 0.0527
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 873
+
+ 0.0845
+
+ 0.053
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1223 0.0105 0.0648
+ pelvis
+
+
+ -0.0309 -0.0047 0.0518
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1000
+
+ 0.0646
+
+ 0.053
+
+ 0.33161256
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.12596 -0.10257 0.06944
+ pelvis
+
+
+ -0.0301 -0.036 0.02943
+ tibia_r
+
+
+ -0.0234 -0.0563 0.0343
+ tibia_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2700
+
+ 0.109
+
+ 0.326
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.005 -0.2111 0.0234
+ femur_r
+
+
+ -0.0301 -0.036 0.02943
+ tibia_r
+
+
+ -0.0234 -0.0563 0.0343
+ tibia_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 804
+
+ 0.173
+
+ 0.089
+
+ 0.40142573
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0153 -0.0013 0.1242
+ pelvis
+
+
+ -0.003 -0.3568 -0.0421
+ femur_r
+
+
+ -0.0056 -0.0419 -0.0399
+ tibia_r
+
+
+ 0.006 -0.0589 -0.0383
+ tibia_r
+
+
+ 0.0243 -0.084 -0.0252
+ tibia_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 156
+
+ 0.52
+
+ 0.1
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0831 -0.1192 0.0308
+ pelvis
+
+
+ 0.0054 -0.2285 0.0227
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2343
+
+ 0.121
+
+ 0.12
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0311 0.0214 0.1241
+ pelvis
+
+
+ 0.0294 -0.0995 0.0597
+ femur_r
+
+
+ 0.0054 -0.4049 0.0357
+ femur_r
+
+
+ 0.006 -0.0487 0.0297
+ tibia_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 233
+
+ 0.095
+
+ 0.425
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0431 -0.0768 0.0451
+ pelvis
+
+
+ -0.0122 -0.0822 0.0253
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 266
+
+ 0.1
+
+ 0.033
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.07401 -0.1187 0.02794
+ pelvis
+
+
+ -0.02657 -0.0319 -0.03774
+ tibia_r
+ -0.436332 0.174533
+ knee_angle_r
+
+
+ -0.01943 -0.05153 -0.0358
+ tibia_r
+
+
+ 0.006 -0.0836 -0.0228
+ tibia_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 162
+
+ 0.352
+
+ 0.126
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1195 0.0612 0.07
+ pelvis
+
+
+ -0.1291 0.0012 0.0886
+ pelvis
+
+
+ -0.0457 -0.0248 0.0392
+ femur_r
+
+
+ -0.0277 -0.0566 0.047
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 573
+
+ 0.142
+
+ 0.125
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1349 0.0176 0.0563
+ pelvis
+
+
+ -0.1376 -0.052 0.0914
+ pelvis
+
+
+ -0.0426 -0.053 0.0293
+ femur_r
+
+
+ -0.0156 -0.1016 0.0419
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 819
+
+ 0.147
+
+ 0.127
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1556 -0.0314 0.0058
+ pelvis
+
+
+ -0.1529 -0.1052 0.0403
+ pelvis
+
+
+ -0.0299 -0.1041 0.0135
+ femur_r
+
+
+ -0.006 -0.1419 0.0411
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 552
+
+ 0.144
+
+ 0.145
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0674 0.0365 0.0854
+ pelvis
+
+
+ -0.0258 -0.055 0.0811
+ pelvis
+
+
+ -0.0288 -0.0805 0.0816
+ pelvis
+ -1.5708 0.785398
+ hip_flexion_r
+
+
+ 0.0017 -0.0543 0.0057
+ femur_r
+
+
+ -0.0193 -0.0621 0.0129
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1073
+
+ 0.1
+
+ 0.1
+
+ 0.12217305
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0647 0.0887 0.0289
+ pelvis
+
+
+ -0.0238 -0.057 0.0759
+ pelvis
+
+
+ -0.0288 -0.0805 0.0816
+ pelvis
+ -1.5708 0.785398
+ hip_flexion_r
+
+
+ 0.0016 -0.0507 0.0038
+ femur_r
+
+
+ -0.0188 -0.0597 0.0104
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1113
+
+ 0.1
+
+ 0.16
+
+ 0.13962634
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1143 -0.1151 0.052
+ pelvis
+
+
+ -0.0381 -0.0359 0.0366
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 381
+
+ 0.054
+
+ 0.024
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1133 -0.082 0.0714
+ pelvis
+
+
+ -0.0142 -0.0033 0.0443
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 164
+
+ 0.024
+
+ 0.039
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1396 0.0003 0.0235
+ pelvis
+
+
+ -0.1193 -0.0276 0.0657
+ pelvis
+
+
+ -0.0148 -0.0036 0.0437
+ femur_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 444
+
+ 0.026
+
+ 0.115
+
+ 0.17453293
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0295 -0.0311 0.0968
+ pelvis
+
+
+ 0.0334 -0.403 0.0019
+ femur_r
+ -2.61799 -1.45997
+ knee_angle_r
+
+
+ 0.0165569 0.0235498 0.0014
+ tibia_r
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0155805 0.0179938 0.0275081 0.0296564 0.0307615 0.0365695 0.0422074 0.0450902 0.048391 0.0534299 0.0617576 0.0617669 0.0617762 0.0633083 0.066994 0.0733035 0.0573481
+
+
+ knee_angle_r
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0234116 0.0237613 0.0251141 0.0252795 0.0253146 0.0249184 0.0242373 0.0238447 0.0234197 0.0227644 0.020984 0.0209814 0.0209788 0.0205225 0.0191754 0.0159554 -0.0673774
+
+
+ knee_angle_r
+
+
+ -2.0944 0.1745
+ 0.0014 0.0014
+
+
+ knee_angle_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1169
+
+ 0.114
+
+ 0.31
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.029 -0.1924 0.031
+ femur_r
+
+
+ 0.0335 -0.2084 0.0285
+ femur_r
+
+
+ 0.0343 -0.403 0.0055
+ femur_r
+ -2.61799 -1.42
+ knee_angle_r
+
+
+ 0.00924963 0.025737 0.0018
+ tibia_r
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0082733 0.0106866 0.0202042 0.022353 0.0234583 0.0292715 0.0349465 0.037871 0.0412569 0.0465287 0.0554632 0.0554735 0.0554837 0.0571717 0.061272 0.0684368 0.0648818
+
+
+ knee_angle_r
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.025599 0.0259487 0.0273124 0.0274796 0.0275151 0.0271363 0.0265737 0.0263073 0.0261187 0.0260129 0.0252923 0.0252911 0.0252898 0.0250526 0.0242191 0.0218288 -0.0685706
+
+
+ knee_angle_r
+
+
+ -2.0944 2.0944
+ 0.0018 0.0018
+
+
+ knee_angle_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 5000
+
+ 0.107
+
+ 0.116
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.019 -0.3929 -0.0235
+ femur_r
+
+
+ -0.03 -0.4022 -0.0258
+ femur_r
+ -0.785398 0.174533
+ knee_angle_r
+
+
+ 0 0.031 -0.0053
+ calcn_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2500
+
+ 0.09
+
+ 0.36
+
+ 0.29670597
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0024 -0.1533 0.0071
+ tibia_r
+
+
+ 0 0.031 -0.0053
+ calcn_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 4000
+
+ 0.05
+
+ 0.25
+
+ 0.43633231
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0094 -0.1348 0.0019
+ tibia_r
+
+
+ -0.0144 -0.4051 -0.0229
+ tibia_r
+
+
+ 0.0417 0.0334 -0.0286
+ calcn_r
+
+
+ 0.0772 0.0159 -0.0281
+ calcn_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 3600
+
+ 0.031
+
+ 0.31
+
+ 0.20943951
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0179 -0.1624 0.0115
+ tibia_r
+
+
+ 0.0329 -0.3951 -0.0177
+ tibia_r
+
+
+ 0.1166 0.0178 -0.0305
+ calcn_r
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 3000
+
+ 0.098
+
+ 0.223
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0408 0.0304 -0.1209
+ pelvis
+
+
+ -0.0218 -0.0117 -0.0555
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1119
+
+ 0.0535
+
+ 0.078
+
+ 0.13962634
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0855 0.0445 -0.0766
+ pelvis
+
+
+ -0.0258 -0.0058 -0.0527
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 873
+
+ 0.0845
+
+ 0.053
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1223 0.0105 -0.0648
+ pelvis
+
+
+ -0.0309 -0.0047 -0.0518
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1000
+
+ 0.0646
+
+ 0.053
+
+ 0.33161256
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.12596 -0.10257 -0.06944
+ pelvis
+
+
+ -0.0301 -0.036 -0.02943
+ tibia_l
+
+
+ -0.0234 -0.0563 -0.0343
+ tibia_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2700
+
+ 0.109
+
+ 0.326
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.005 -0.2111 -0.0234
+ femur_l
+
+
+ -0.0301 -0.036 -0.02943
+ tibia_l
+
+
+ -0.0234 -0.0563 -0.0343
+ tibia_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 804
+
+ 0.173
+
+ 0.089
+
+ 0.40142573
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0153 -0.0013 -0.1242
+ pelvis
+
+
+ -0.003 -0.3568 0.0421
+ femur_l
+
+
+ -0.0056 -0.0419 0.0399
+ tibia_l
+
+
+ 0.006 -0.0589 0.0383
+ tibia_l
+
+
+ 0.0243 -0.084 0.0252
+ tibia_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 156
+
+ 0.52
+
+ 0.1
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0831 -0.1192 -0.0308
+ pelvis
+
+
+ 0.0054 -0.2285 -0.0227
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2343
+
+ 0.121
+
+ 0.12
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0311 0.0214 -0.1241
+ pelvis
+
+
+ 0.0294 -0.0995 -0.0597
+ femur_l
+
+
+ 0.0054 -0.4049 -0.0357
+ femur_l
+
+
+ 0.006 -0.0487 -0.0297
+ tibia_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 233
+
+ 0.095
+
+ 0.425
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0431 -0.0768 -0.0451
+ pelvis
+
+
+ -0.0122 -0.0822 -0.0253
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 266
+
+ 0.1
+
+ 0.033
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.07401 -0.1187 -0.02794
+ pelvis
+
+
+ -0.02657 -0.0319 0.03774
+ tibia_l
+ -0.436332 0.174533
+ knee_angle_l
+
+
+ -0.01943 -0.05153 0.0358
+ tibia_l
+
+
+ 0.006 -0.0836 0.0228
+ tibia_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 162
+
+ 0.352
+
+ 0.126
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1195 0.0612 -0.07
+ pelvis
+
+
+ -0.1291 0.0012 -0.0886
+ pelvis
+
+
+ -0.0457 -0.0248 -0.0392
+ femur_l
+
+
+ -0.0277 -0.0566 -0.047
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 573
+
+ 0.142
+
+ 0.125
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1349 0.0176 -0.0563
+ pelvis
+
+
+ -0.1376 -0.052 -0.0914
+ pelvis
+
+
+ -0.0426 -0.053 -0.0293
+ femur_l
+
+
+ -0.0156 -0.1016 -0.0419
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 819
+
+ 0.147
+
+ 0.127
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1556 -0.0314 -0.0058
+ pelvis
+
+
+ -0.1529 -0.1052 -0.0403
+ pelvis
+
+
+ -0.0299 -0.1041 -0.0135
+ femur_l
+
+
+ -0.006 -0.1419 -0.0411
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 552
+
+ 0.144
+
+ 0.145
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0674 0.0365 -0.0854
+ pelvis
+
+
+ -0.0258 -0.055 -0.0811
+ pelvis
+
+
+ -0.0288 -0.0805 -0.0816
+ pelvis
+ -1.5708 0.785398
+ hip_flexion_l
+
+
+ 0.0017 -0.0543 -0.0057
+ femur_l
+
+
+ -0.0193 -0.0621 -0.0129
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1073
+
+ 0.1
+
+ 0.1
+
+ 0.12217305
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0647 0.0887 -0.0289
+ pelvis
+
+
+ -0.0238 -0.057 -0.0759
+ pelvis
+
+
+ -0.0288 -0.0805 -0.0816
+ pelvis
+ -1.5708 0.785398
+ hip_flexion_l
+
+
+ 0.0016 -0.0507 -0.0038
+ femur_l
+
+
+ -0.0188 -0.0597 -0.0104
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1113
+
+ 0.1
+
+ 0.16
+
+ 0.13962634
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1143 -0.1151 -0.052
+ pelvis
+
+
+ -0.0381 -0.0359 -0.0366
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 381
+
+ 0.054
+
+ 0.024
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1133 -0.082 -0.0714
+ pelvis
+
+
+ -0.0142 -0.0033 -0.0443
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 164
+
+ 0.024
+
+ 0.039
+
+ 0
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.1396 0.0003 -0.0235
+ pelvis
+
+
+ -0.1193 -0.0276 -0.0657
+ pelvis
+
+
+ -0.0148 -0.0036 -0.0437
+ femur_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 444
+
+ 0.026
+
+ 0.115
+
+ 0.17453293
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0295 -0.0311 -0.0968
+ pelvis
+
+
+ 0.0334 -0.403 -0.0019
+ femur_l
+ -2.61799 -1.45997
+ knee_angle_l
+
+
+ 0.0407382 0.0244256 -0.0014
+ tibia_l
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0155805 0.0179938 0.0275081 0.0296564 0.0307615 0.0365695 0.0422074 0.0450902 0.048391 0.0534299 0.0617576 0.0617669 0.0617762 0.0633083 0.066994 0.0733035 0.0573481
+
+
+ knee_angle_l
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0234116 0.0237613 0.0251141 0.0252795 0.0253146 0.0249184 0.0242373 0.0238447 0.0234197 0.0227644 0.020984 0.0209814 0.0209788 0.0205225 0.0191754 0.0159554 -0.0673774
+
+
+ knee_angle_l
+
+
+ -2.0944 0.1745
+ -0.0014 -0.0014
+
+
+ knee_angle_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 1169
+
+ 0.114
+
+ 0.31
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.029 -0.1924 -0.031
+ femur_l
+
+
+ 0.0335 -0.2084 -0.0285
+ femur_l
+
+
+ 0.0343 -0.403 -0.0055
+ femur_l
+ -2.61799 -1.42
+ knee_angle_l
+
+
+ 0.0334625 0.0267161 -0.0018
+ tibia_l
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.0082733 0.0106866 0.0202042 0.022353 0.0234583 0.0292715 0.0349465 0.037871 0.0412569 0.0465287 0.0554632 0.0554735 0.0554837 0.0571717 0.061272 0.0684368 0.0648818
+
+
+ knee_angle_l
+
+
+ -2.0944 -1.99997 -1.5708 -1.45752 -1.39626 -1.0472 -0.698132 -0.526391 -0.349066 -0.174533 0 0.00017453 0.00034907 0.0279253 0.0872665 0.174533 2.0944
+ 0.025599 0.0259487 0.0273124 0.0274796 0.0275151 0.0271363 0.0265737 0.0263073 0.0261187 0.0260129 0.0252923 0.0252911 0.0252898 0.0250526 0.0242191 0.0218288 -0.0685706
+
+
+ knee_angle_l
+
+
+ -2.0944 2.0944
+ -0.0018 -0.0018
+
+
+ knee_angle_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 5000
+
+ 0.107
+
+ 0.116
+
+ 0.05235988
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.019 -0.3929 0.0235
+ femur_l
+
+
+ -0.03 -0.4022 0.0258
+ femur_l
+ -0.785398 0.174533
+ knee_angle_l
+
+
+ 0 0.031 0.0053
+ calcn_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 2500
+
+ 0.09
+
+ 0.36
+
+ 0.29670597
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0024 -0.1533 -0.0071
+ tibia_l
+
+
+ 0 0.031 0.0053
+ calcn_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 4000
+
+ 0.05
+
+ 0.25
+
+ 0.43633231
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0094 -0.1348 -0.0019
+ tibia_l
+
+
+ -0.0144 -0.4051 0.0229
+ tibia_l
+
+
+ 0.0417 0.0334 0.0286
+ calcn_l
+
+
+ 0.0772 0.0159 0.0281
+ calcn_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 3600
+
+ 0.031
+
+ 0.31
+
+ 0.20943951
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0179 -0.1624 -0.0115
+ tibia_l
+
+
+ 0.0329 -0.3951 0.0177
+ tibia_l
+
+
+ 0.1166 0.0178 0.0305
+ calcn_l
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0 0 -0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1
+
+ 3000
+
+ 0.098
+
+ 0.223
+
+ 0.08726646
+
+ 10
+
+ 0.01
+
+ 0.04
+
+ 0.033
+
+ 0.6
+
+ 0.5
+
+ 4
+
+ 0.3
+
+ 1.8
+
+
+
+
+ glut_max1_r glut_med1_r glut_med2_r glut_med3_r peri_r sar_r tfl_r
+
+
+ glut_med1_r grac_r iliacus_r pect_r psoas_r rect_fem_r sar_r tfl_r
+
+
+ glut_med1_r iliacus_r psoas_r tfl_r
+
+
+ gem_r glut_med3_r peri_r quad_fem_r
+
+
+ add_mag2_r bifemlh_r glut_max1_r glut_max2_r glut_max3_r glut_med3_r
+
+
+ add_mag2_r bifemlh_r grac_r pect_r
+
+
+ bifemlh_r bifemsh_r grac_r med_gas_r sar_r
+
+
+ rect_fem_r vas_int_r
+
+
+ med_gas_r soleus_r tib_post_r
+
+
+ tib_ant_r tib_post_r
+
+
+ tib_ant_r
+
+
+ glut_max1_l glut_med1_l glut_med2_l glut_med3_l peri_l sar_l tfl_l
+
+
+ glut_med1_l grac_l iliacus_l pect_l psoas_l rect_fem_l sar_l tfl_l
+
+
+ glut_med1_l iliacus_l psoas_l tfl_l
+
+
+ gem_l glut_med3_l peri_l quad_fem_l
+
+
+ add_mag2_l bifemlh_l glut_max1_l glut_max2_l glut_max3_l glut_med3_l
+
+
+ add_mag2_l bifemlh_l grac_l pect_l
+
+
+ bifemlh_l bifemsh_l grac_l med_gas_l sar_l
+
+
+ rect_fem_l vas_int_l
+
+
+ med_gas_l soleus_l tib_post_l
+
+
+ tib_ant_l tib_post_l
+
+
+ tib_ant_l
+
+
+
+
+
+
+
+
+ frame
+
+ 0.00114552 0.376431 -0.379321
+
+ true
+
+
+
+ frame
+
+ -0.0366384 -0.291526 -0.20305
+
+ true
+
+
+
+ gears
+
+ 0.118742 -0.113054 0.159427
+
+ true
+
+
+
+ gears
+
+ -0.0810048 0.109176 -0.179171
+
+ true
+
+
+
+ frame
+
+ 0.00640082 -0.245379 -0.685729
+
+ true
+
+
+
+ frame
+
+ 0.00274065 -0.23821 0.505443
+
+ true
+
+
+
+ saddle
+
+ 0 0.0972512 0.0434398
+
+ true
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/frame.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/frame.obj
new file mode 100644
index 0000000000..3cf82f0e61
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/frame.obj
@@ -0,0 +1,4129 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object frame.obj
+#
+# Vertices: 1445
+# Faces: 2668
+#
+####
+v 0.004407 0.406782 0.575197
+v 0.032872 0.406782 0.575197
+v 0.036157 0.406782 0.575197
+v -0.070041 -0.011635 0.867525
+v -0.079894 -0.022974 0.859932
+v -0.062924 -0.028644 0.818171
+v -0.074967 -0.035447 0.825764
+v -0.070041 0.065472 0.840950
+v -0.062924 0.048463 0.795392
+v -0.104528 0.070008 0.856136
+v -0.104528 -0.007099 0.882711
+v -0.104528 -0.019572 0.871322
+v -0.104528 -0.038849 0.791596
+v -0.104528 -0.042251 0.806782
+v -0.074967 -0.436855 0.962437
+v -0.104528 -0.457265 0.947251
+v -0.104528 -0.520765 1.042163
+v -0.104528 -0.434587 1.011792
+v -0.129161 -0.538907 0.985216
+v -0.105075 -0.483346 1.080128
+v -0.080989 -0.486747 1.072535
+v -0.079894 -0.524166 1.030774
+v -0.104528 -0.542309 0.973827
+v -0.105075 -0.434587 1.064942
+v -0.080989 -0.437989 1.057349
+v -0.079894 -0.437989 1.000402
+v -0.085916 0.362559 0.727056
+v -0.081536 0.058668 0.799189
+v -0.082084 0.354622 0.700480
+v -0.085368 0.067740 0.825764
+v -0.104528 0.365961 0.730852
+v -0.103980 0.070008 0.833357
+v -0.083179 0.381836 0.723259
+v -0.104528 0.385237 0.730852
+v -0.078799 0.370496 0.692887
+v -0.104528 0.363693 0.673905
+v -0.145583 0.059802 0.825764
+v -0.145583 -0.017304 0.852339
+v -0.134088 -0.027510 0.848543
+v -0.134088 -0.428917 0.985216
+v -0.129161 -0.038849 0.814375
+v -0.129161 -0.453863 0.954844
+v -0.139014 -0.034313 0.802985
+v -0.139014 0.042793 0.776410
+v -0.104528 0.038258 0.765021
+v -0.122592 0.055267 0.787799
+v -0.126424 0.064338 0.814375
+v -0.126971 0.360291 0.715666
+v -0.130256 0.378434 0.711870
+v -0.125329 0.367095 0.681498
+v -0.123140 0.351220 0.689091
+v -0.104528 0.348952 0.681498
+v -0.103980 0.052999 0.784003
+v 0.088708 -0.524166 1.030774
+v 0.137975 -0.538907 0.985216
+v 0.113341 -0.520765 1.042163
+v 0.089803 -0.486747 1.072535
+v 0.113889 -0.483346 1.080128
+v 0.113341 -0.542309 0.973827
+v 0.137975 -0.453863 0.954844
+v 0.113341 -0.457265 0.947251
+v 0.112794 0.070008 0.833357
+v 0.154397 0.059802 0.825764
+v 0.135238 0.064338 0.814375
+v 0.078855 0.065472 0.840950
+v 0.094182 0.067740 0.825764
+v 0.071738 0.048463 0.795392
+v 0.090350 0.058668 0.799189
+v 0.094729 0.362559 0.727056
+v 0.113341 0.365961 0.730852
+v 0.135785 0.360291 0.715666
+v 0.131953 0.351220 0.689091
+v 0.131406 0.055267 0.787799
+v 0.147828 0.042793 0.776410
+v 0.154397 -0.017304 0.852339
+v 0.139070 0.378434 0.711870
+v 0.134143 0.367095 0.681498
+v 0.113341 0.363693 0.673905
+v 0.113341 0.348952 0.681498
+v 0.112794 0.052999 0.784003
+v 0.147828 -0.034313 0.802985
+v 0.137975 -0.038849 0.814375
+v 0.142902 -0.027510 0.848543
+v 0.142902 -0.428917 0.985216
+v 0.113341 -0.019572 0.871322
+v 0.113341 -0.007099 0.882711
+v 0.113341 0.070008 0.856136
+v 0.071738 -0.028644 0.818171
+v 0.078855 -0.011635 0.867525
+v 0.088708 -0.022974 0.859932
+v 0.083781 -0.035447 0.825764
+v 0.113341 -0.434587 1.011792
+v 0.083781 -0.436855 0.962437
+v 0.113341 -0.038849 0.791596
+v 0.113341 0.038258 0.765021
+v 0.090898 0.354622 0.700480
+v 0.087613 0.370496 0.692887
+v 0.091992 0.381836 0.723259
+v 0.113341 0.385237 0.730852
+v -0.106717 0.369362 0.772613
+v -0.066756 0.369362 0.765021
+v -0.079894 0.418121 0.757428
+v 0.019734 0.446469 0.746038
+v 0.046557 0.393175 0.757428
+v 0.088708 0.418121 0.757428
+v 0.075570 0.369362 0.765021
+v 0.115531 0.369362 0.772613
+v 0.115531 0.363693 0.757428
+v -0.010921 0.446469 0.746038
+v -0.079894 0.412451 0.742242
+v -0.010921 0.440799 0.730852
+v 0.004407 0.446469 0.746038
+v -0.106717 0.160721 0.833357
+v -0.106717 0.363693 0.757428
+v -0.076610 0.164123 0.840950
+v 0.004407 0.393175 0.757428
+v 0.004407 0.440799 0.730852
+v 0.019734 0.440799 0.730852
+v -0.020774 0.851279 0.487878
+v 0.004407 0.859215 0.510656
+v 0.004407 0.844475 0.465099
+v 0.058600 0.001972 -0.776350
+v 0.066264 0.170927 -0.943395
+v 0.066264 0.008776 -0.768757
+v 0.004407 0.018981 -0.753571
+v 0.004407 0.183400 -0.935802
+v 0.004407 0.282051 -1.152201
+v 0.066264 0.267310 -1.155998
+v 0.058600 0.223087 -1.676115
+v 0.066264 0.234426 -1.679911
+v 0.058600 0.285453 -1.455919
+v 0.066264 0.296792 -1.455919
+v 0.004407 0.312667 -1.455919
+v -0.057450 0.296792 -1.455919
+v -0.057450 0.267310 -1.155998
+v -0.057450 0.170927 -0.943395
+v -0.057450 0.008776 -0.768757
+v -0.057450 0.234426 -1.679911
+v -0.049787 0.285453 -1.455919
+v 0.004407 0.248034 -1.687504
+v 0.066264 0.106294 -1.892514
+v 0.004407 0.117632 -1.903904
+v -0.057450 0.106294 -1.892514
+v -0.051976 -0.029777 -1.998815
+v -0.057450 -0.024107 -2.010205
+v -0.021869 -0.037714 -2.021594
+v -0.049787 0.223087 -1.676115
+v -0.049787 0.097222 -1.884921
+v 0.004407 0.235560 -1.683708
+v 0.060790 -0.029777 -1.998815
+v 0.058600 0.097222 -1.884921
+v 0.003859 -0.002563 -2.006409
+v 0.029040 -0.039982 -2.006409
+v -0.020227 -0.039982 -2.006409
+v 0.004407 0.107427 -1.892514
+v -0.049787 0.257105 -1.159794
+v 0.004407 0.269578 -1.155998
+v -0.049787 0.160721 -0.950988
+v 0.004407 0.172061 -0.943395
+v -0.049787 0.001972 -0.776350
+v 0.004407 0.009910 -0.764960
+v 0.004407 -0.108018 -0.692827
+v 0.058600 0.257105 -1.159794
+v 0.058600 0.160721 -0.950988
+v 0.060790 -0.130696 -0.692827
+v 0.030135 -0.148839 -0.681438
+v -0.051976 -0.130696 -0.692827
+v -0.112191 -0.416444 -1.353414
+v -0.055261 0.212882 -0.814314
+v -0.099054 -0.403971 -1.364804
+v -0.042123 0.191337 -0.795332
+v -0.067851 0.198141 -0.787739
+v -0.039933 0.268444 -0.764960
+v -0.055261 0.176596 -0.772553
+v -0.099054 -0.430051 -1.338228
+v -0.027890 0.243497 -0.749774
+v -0.039933 0.231024 -0.723199
+v -0.051976 0.257105 -0.734588
+v -0.003257 0.324006 -0.711809
+v -0.003257 0.286587 -0.673845
+v 0.004407 0.314935 -0.685234
+v 0.027398 -0.605809 -0.495410
+v 0.038346 -0.579728 -0.484021
+v 0.012618 -0.610344 -0.457446
+v 0.069549 -0.570657 -0.586526
+v 0.058053 -0.597871 -0.594119
+v 0.027398 -0.551380 -0.491614
+v 0.058053 -0.542309 -0.590322
+v 0.004407 -0.564987 -0.457446
+v 0.004407 -0.567255 -0.465039
+v 0.012618 -0.554782 -0.453649
+v -0.049239 -0.542309 -0.590322
+v -0.060735 -0.570657 -0.586526
+v -0.018584 -0.551380 -0.491614
+v -0.029533 -0.579728 -0.484021
+v -0.003804 -0.554782 -0.453649
+v 0.004407 -0.583130 -0.449853
+v -0.003804 -0.610344 -0.457446
+v -0.018584 -0.605809 -0.495410
+v 0.004407 -0.577460 -0.503003
+v -0.049239 -0.597871 -0.594119
+v -0.038291 -0.569523 -0.597915
+v -0.098506 -0.483345 -1.330635
+v 0.004407 -0.612612 -0.427074
+v 0.004407 -0.599005 -0.461242
+v 0.107867 -0.403971 -1.364804
+v 0.064075 0.212882 -0.814314
+v 0.121005 -0.416444 -1.353414
+v 0.048747 0.231024 -0.723199
+v 0.060790 0.257105 -0.734588
+v 0.012071 0.286587 -0.673845
+v 0.004407 0.289988 -0.700420
+v 0.036704 0.243497 -0.749774
+v 0.064075 0.176596 -0.772553
+v 0.050937 0.191337 -0.795332
+v 0.107867 -0.430051 -1.338228
+v 0.094729 -0.417578 -1.353414
+v 0.076665 0.198141 -0.787739
+v 0.048747 0.268444 -0.764960
+v -0.004352 0.328542 -0.689031
+v 0.036157 0.660780 0.556214
+v 0.027946 0.292256 -0.677641
+v -0.007636 0.697065 0.544825
+v -0.024606 0.292256 -0.677641
+v -0.035007 0.660780 0.556214
+v 0.101846 0.234426 0.833357
+v 0.029040 0.322872 0.799189
+v 0.090350 0.233292 0.825764
+v 0.101846 0.183399 0.840950
+v 0.101846 0.185667 0.852339
+v 0.101846 0.231024 0.821968
+v 0.031230 0.320604 0.791596
+v 0.004407 0.320604 0.791596
+v 0.004407 0.322872 0.799189
+v -0.020227 0.322872 0.799189
+v -0.022416 0.320604 0.791596
+v -0.020227 0.317202 0.799189
+v -0.081536 0.233292 0.825764
+v 0.004407 0.317202 0.799189
+v 0.029040 0.317202 0.799189
+v -0.070041 0.189069 0.844747
+v -0.093032 0.183399 0.840950
+v -0.093032 0.231024 0.821968
+v -0.093032 0.234426 0.833357
+v -0.061282 0.152784 0.859932
+v -0.093032 0.185667 0.852339
+v 0.004407 0.465746 -0.772553
+v 0.004407 -0.601273 -0.449853
+v -0.028438 0.478219 -0.734588
+v -0.028438 -0.589934 -0.408091
+v 0.004407 0.489558 -0.696624
+v 0.004407 -0.577460 -0.370127
+v 0.037251 0.478219 -0.734588
+v 0.037251 -0.589934 -0.408091
+v 0.254026 0.980545 0.696684
+v 0.229940 0.980545 0.696684
+v 0.254026 0.991885 0.689091
+v 0.228297 0.991885 0.689091
+v 0.198190 0.977143 0.696684
+v 0.193811 0.987349 0.689091
+v 0.227203 1.005491 0.689091
+v 0.128121 0.936323 0.696684
+v 0.124837 0.947661 0.689091
+v 0.152755 0.951063 0.696684
+v 0.146733 0.960135 0.689091
+v 0.170819 0.977143 0.689091
+v 0.188884 0.999821 0.689091
+v 0.225560 1.015697 0.696684
+v 0.227203 1.005491 0.727056
+v 0.254026 1.015697 0.719463
+v 0.225560 1.015697 0.719463
+v 0.184505 1.010027 0.696684
+v 0.225013 1.020233 0.708074
+v 0.163156 0.987349 0.689091
+v 0.139617 0.971473 0.689091
+v 0.102393 0.957867 0.689091
+v 0.102941 0.945393 0.689091
+v 0.004407 0.945393 0.689091
+v 0.120458 0.960135 0.689091
+v 0.117173 0.970339 0.696684
+v 0.133596 0.980545 0.696684
+v 0.157134 0.996421 0.696684
+v 0.182862 1.014563 0.708074
+v -0.162006 0.977143 0.689091
+v -0.180070 0.999821 0.689091
+v -0.154342 0.987349 0.689091
+v -0.130803 0.971473 0.689091
+v -0.137920 0.960135 0.689091
+v -0.111644 0.960135 0.689091
+v -0.116023 0.947661 0.689091
+v -0.094127 0.945393 0.689091
+v 0.004407 0.934055 0.696684
+v -0.216747 1.015697 0.696684
+v -0.218389 1.005491 0.689091
+v -0.245212 1.015697 0.696684
+v -0.184997 0.987349 0.689091
+v -0.245212 1.005491 0.689091
+v -0.219484 0.991885 0.689091
+v -0.189376 0.977143 0.719463
+v -0.219484 0.991885 0.727056
+v -0.221126 0.980545 0.719463
+v -0.170217 0.964671 0.708074
+v -0.191018 0.973741 0.708074
+v -0.221126 0.977143 0.708074
+v -0.189376 0.977143 0.696684
+v -0.168027 0.968071 0.696684
+v -0.245212 0.991885 0.727056
+v -0.245212 1.005491 0.727056
+v -0.218389 1.005491 0.727056
+v -0.216199 1.020233 0.708074
+v -0.175691 1.010027 0.696684
+v -0.175691 1.010027 0.719463
+v -0.216747 1.015697 0.719463
+v -0.180070 0.999821 0.727056
+v -0.174049 1.014563 0.708074
+v -0.148320 0.996421 0.696684
+v -0.124782 0.980545 0.696684
+v -0.108359 0.970339 0.696684
+v -0.154342 0.987349 0.727056
+v -0.148320 0.996421 0.719463
+v -0.145583 0.999821 0.708074
+v -0.122592 0.983947 0.708074
+v -0.106717 0.974875 0.708074
+v -0.093032 0.969205 0.696684
+v -0.130803 0.971473 0.727056
+v -0.162006 0.977143 0.727056
+v -0.137920 0.960135 0.727056
+v -0.124782 0.980545 0.719463
+v -0.108359 0.970339 0.719463
+v -0.111644 0.960135 0.727056
+v -0.116023 0.947661 0.727056
+v -0.143941 0.951063 0.719463
+v -0.168027 0.968071 0.719463
+v -0.184997 0.987349 0.727056
+v -0.119308 0.936323 0.719463
+v -0.146131 0.947661 0.708074
+v -0.094127 0.945393 0.727056
+v 0.004407 0.934055 0.719463
+v 0.004407 0.945393 0.727056
+v -0.095222 0.934055 0.719463
+v -0.095222 0.929519 0.708074
+v -0.120402 0.932921 0.708074
+v -0.119308 0.936323 0.696684
+v -0.143941 0.951063 0.696684
+v -0.095222 0.934055 0.696684
+v 0.004407 0.929519 0.708074
+v 0.104035 0.929519 0.708074
+v 0.104035 0.934055 0.719463
+v 0.104035 0.934055 0.696684
+v 0.128121 0.936323 0.719463
+v 0.129216 0.932921 0.708074
+v 0.124837 0.947661 0.727056
+v 0.102941 0.945393 0.727056
+v 0.154945 0.947661 0.708074
+v 0.152755 0.951063 0.719463
+v 0.004407 0.957867 0.727056
+v 0.102393 0.957867 0.727056
+v 0.120458 0.960135 0.727056
+v 0.146733 0.960135 0.727056
+v 0.176841 0.968071 0.719463
+v 0.179031 0.964671 0.708074
+v 0.004407 0.969205 0.719463
+v 0.101846 0.969205 0.719463
+v 0.117173 0.970339 0.719463
+v 0.139617 0.971473 0.727056
+v 0.101846 0.973741 0.708074
+v 0.004407 0.973741 0.708074
+v 0.115531 0.974875 0.708074
+v 0.133596 0.980545 0.719463
+v 0.163156 0.987349 0.727056
+v 0.170819 0.977143 0.727056
+v 0.157134 0.996421 0.719463
+v 0.131406 0.983947 0.708074
+v 0.154397 0.999821 0.708074
+v 0.184505 1.010027 0.719463
+v 0.188884 0.999821 0.727056
+v 0.193811 0.987349 0.727056
+v 0.228297 0.991885 0.727056
+v 0.198190 0.977143 0.719463
+v 0.229940 0.980545 0.719463
+v 0.199832 0.973741 0.708074
+v 0.229940 0.977143 0.708074
+v 0.254026 0.977143 0.708074
+v 0.254026 0.980545 0.719463
+v 0.055316 0.728815 0.525842
+v 0.004407 0.741288 0.567604
+v 0.059148 0.413585 0.628347
+v -0.050334 0.413585 0.628347
+v -0.046502 0.728815 0.525842
+v 0.004407 0.712940 0.480285
+v 0.004407 0.971473 0.696684
+v 0.025208 0.960135 0.704277
+v 0.004407 0.860349 0.529639
+v -0.016395 0.960135 0.704277
+v -0.016395 0.845609 0.537232
+v -0.013110 0.830867 0.563807
+v -0.013110 0.803653 0.541028
+v 0.004407 0.825199 0.567604
+v 0.004407 0.792315 0.544825
+v 0.004407 0.837671 0.491674
+v -0.016395 0.800251 0.503064
+v 0.021924 0.938591 0.719463
+v 0.004407 0.934055 0.723259
+v 0.021924 0.830867 0.563807
+v 0.025208 0.845609 0.537232
+v 0.021924 0.803653 0.541028
+v 0.025208 0.800251 0.503064
+v 0.021924 0.732217 0.525842
+v 0.034514 0.741288 0.522046
+v 0.004407 0.733351 0.495471
+v 0.029588 0.851279 0.487878
+v 0.009881 0.530379 0.746038
+v 0.003859 0.495227 0.738445
+v 0.005502 0.531513 0.742242
+v 0.010428 0.558727 0.746038
+v 0.022471 0.618825 0.753631
+v 0.020282 0.583673 0.753631
+v 0.015903 0.585941 0.749835
+v 0.026303 0.617691 0.757428
+v 0.031777 0.667583 0.761224
+v 0.018092 0.618825 0.757428
+v 0.020282 0.793449 0.765021
+v 0.031777 0.739020 0.761224
+v 0.027398 0.739020 0.768817
+v 0.027946 0.667583 0.757428
+v -0.031175 0.909109 0.753631
+v 0.002217 0.852413 0.757428
+v -0.035007 0.906841 0.757428
+v 0.024114 0.794583 0.761224
+v 0.036157 0.739020 0.768817
+v 0.027946 0.795717 0.765021
+v -0.211272 1.045179 0.742242
+v -0.211272 1.041777 0.746038
+v -0.290647 1.051983 0.765021
+v -0.165838 1.032705 0.742242
+v -0.289552 1.047447 0.768817
+v 0.002217 0.531513 0.746038
+v -0.000520 0.495227 0.742242
+v 0.005502 0.530379 0.749835
+v 0.006049 0.558727 0.749835
+v 0.010428 0.557593 0.753631
+v 0.012071 0.585941 0.753631
+v 0.015903 0.584807 0.757428
+v 0.014260 0.557593 0.749835
+v -0.027890 0.911375 0.757428
+v 0.002217 0.852413 0.765021
+v 0.005502 0.854679 0.761224
+v 0.024114 0.794583 0.768817
+v -0.072778 0.961269 0.753631
+v -0.070041 0.963537 0.749835
+v -0.118760 1.003223 0.749835
+v -0.031722 0.909109 0.761224
+v -0.001615 0.851279 0.761224
+v -0.210178 1.045179 0.749835
+v -0.167480 1.029303 0.746038
+v -0.165838 1.032705 0.749835
+v -0.121497 0.999821 0.746038
+v -0.076062 0.957867 0.749835
+v -0.164195 1.036107 0.746038
+v -0.210178 1.049715 0.746038
+v -0.116571 1.006625 0.746038
+v 0.003859 0.494094 0.746038
+v 0.004407 0.443067 0.742242
+v 0.000575 0.319470 0.795392
+v 0.004407 0.321738 0.799189
+v 0.007691 0.495227 0.742242
+v 0.008239 0.441933 0.738445
+v 0.004407 0.440799 0.734649
+v 0.000575 0.441933 0.738445
+v 0.004407 0.318336 0.791596
+v -0.076610 -0.681781 -0.305587
+v -0.071136 -0.736209 -0.400499
+v -0.071136 -0.686317 -0.301790
+v -0.071136 -0.726004 -0.404295
+v -0.071136 -0.678379 -0.309383
+v -0.071136 -0.625085 -0.267622
+v -0.076610 -0.623951 -0.275215
+v -0.076610 -0.552514 -0.271418
+v -0.071136 -0.551380 -0.267622
+v -0.076610 -0.498086 -0.297993
+v -0.071136 -0.495818 -0.294197
+v -0.076610 -0.458399 -0.343551
+v -0.071136 -0.453863 -0.343551
+v -0.071136 -0.440256 -0.411888
+v -0.076610 -0.409640 -1.391379
+v -0.071136 -0.403971 -1.391379
+v -0.071136 -0.462935 -0.347348
+v -0.071136 -0.554782 -0.279011
+v -0.076610 -0.731674 -0.400499
+v -0.071136 -0.887021 -1.239520
+v -0.076610 -0.881351 -1.239520
+v -0.071136 -0.891556 -1.300264
+v -0.076610 -0.885887 -1.300264
+v -0.071136 -0.881351 -1.296467
+v -0.071136 -0.867744 -1.334432
+v -0.076610 -0.864342 -1.330635
+v -0.076610 -0.681781 -1.235724
+v -0.071136 -0.680647 -1.239520
+v -0.076610 -0.826923 -1.326839
+v -0.071136 -0.824655 -1.334432
+v -0.071136 -0.622817 -1.262299
+v -0.071136 -0.613746 -1.254706
+v -0.071136 -0.646630 -1.239520
+v -0.071136 -0.643228 -1.231927
+v -0.071136 -0.684049 -1.228131
+v -0.071136 -0.862074 -1.326839
+v -0.071136 -0.427783 -1.429344
+v -0.071136 -0.460667 -1.448326
+v -0.076610 -0.432319 -1.425547
+v -0.076610 -0.462935 -1.440733
+v -0.071136 -0.518497 -1.433140
+v -0.076610 -0.516229 -1.425547
+v -0.076610 -0.618281 -1.258503
+v -0.076610 -0.645496 -1.235724
+v -0.071136 -0.829191 -1.323043
+v -0.071136 -0.513961 -1.421751
+v -0.071136 -0.464068 -1.436937
+v -0.071136 -0.435720 -1.421751
+v -0.071136 -0.622818 -0.279011
+v -0.071136 -0.501488 -0.301790
+v -0.051976 0.523576 0.590383
+v -0.051976 0.505433 0.582790
+v -0.049787 0.509969 0.578993
+v -0.044860 0.491826 0.575197
+v -0.049787 0.491826 0.571400
+v -0.039386 0.477085 0.560011
+v -0.034459 0.478219 0.563807
+v -0.027343 0.464612 0.548621
+v -0.022964 0.464612 0.552418
+v -0.015847 0.451005 0.537232
+v -0.010921 0.452138 0.541028
+v -0.005994 0.438531 0.525842
+v -0.021321 0.469147 0.548621
+v -0.032817 0.482754 0.560011
+v -0.042670 0.496361 0.571400
+v -0.054713 0.509969 0.578993
+v -0.037744 0.481621 0.556214
+v -0.025701 0.468014 0.544825
+v -0.014205 0.455540 0.533435
+v -0.009278 0.456674 0.537232
+v -0.003804 0.443067 0.522046
+v 0.001670 0.728815 0.727056
+v -0.001067 0.686860 0.700480
+v -0.006541 0.689128 0.696684
+v -0.015847 0.644905 0.670109
+v -0.057450 0.524710 0.586586
+v -0.054166 0.520174 0.594179
+v -0.048144 0.559861 0.620754
+v -0.045955 0.563263 0.616958
+v -0.034459 0.601816 0.647330
+v -0.032270 0.604084 0.643533
+v -0.018037 0.642637 0.677702
+v -0.003257 0.683458 0.704277
+v 0.004407 0.724279 0.730852
+v -0.023511 0.644905 0.673905
+v -0.008731 0.685726 0.704277
+v -0.000520 0.726547 0.730852
+v -0.002162 0.765100 0.761224
+v 0.006597 0.727681 0.727056
+v 0.002765 0.765100 0.761224
+v -0.019132 0.802519 0.787799
+v -0.016942 0.805921 0.784003
+v -0.014752 0.803653 0.791596
+v -0.012563 0.808189 0.787799
+v 0.004407 0.768502 0.757428
+v -0.065662 0.835403 0.799189
+v -0.063472 0.838805 0.802985
+v -0.060735 0.842207 0.799189
+v 0.000028 0.768502 0.757428
+v -0.115476 0.873957 0.802985
+v -0.112739 0.877359 0.799189
+v -0.168575 0.906841 0.787799
+v -0.117118 0.869421 0.799189
+v -0.063472 0.839939 0.795392
+v -0.114381 0.872823 0.795392
+v -0.165838 0.909109 0.784003
+v -0.166932 0.905707 0.780207
+v -0.216199 0.938591 0.768817
+v -0.219484 0.935189 0.772613
+v -0.169669 0.902305 0.784003
+v -0.264919 0.959001 0.757428
+v -0.261634 0.962403 0.753631
+v -0.220031 0.931787 0.768817
+v -0.265466 0.954465 0.753631
+v -0.217294 0.934055 0.765021
+v -0.302142 0.970339 0.742242
+v -0.301048 0.974875 0.746038
+v -0.299405 0.978277 0.742242
+v -0.262729 0.957867 0.749835
+v -0.326228 0.980545 0.738445
+v -0.327323 0.977143 0.742242
+v -0.326228 0.980545 0.746038
+v -0.325134 0.985081 0.742242
+v -0.021321 0.647173 0.670109
+v -0.037744 0.606352 0.643533
+v -0.039933 0.604084 0.647330
+v -0.051429 0.565531 0.616958
+v -0.053619 0.562129 0.620754
+v -0.059640 0.521308 0.594179
+v -0.056903 0.506567 0.582790
+v -0.047597 0.495227 0.567604
+v 0.006049 -0.631889 -0.373923
+v -0.001067 -0.644362 -0.389109
+v 0.004407 -0.647764 -0.385313
+v 0.001122 -0.630755 -0.373923
+v 0.001122 0.426058 0.514453
+v -0.001067 0.438531 0.529639
+v 0.006049 0.426058 0.518249
+v 0.007691 0.429460 0.514453
+v 0.001122 0.443067 0.525842
+v 0.002765 0.430594 0.510656
+v 0.007691 -0.628487 -0.377720
+v 0.006049 -0.643228 -0.389109
+v -0.001067 -0.654567 -0.404295
+v -0.005994 -0.651165 -0.404295
+v 0.001122 -0.640960 -0.389109
+v 0.001122 -0.648897 -0.404295
+v -0.003257 -0.645496 -0.404295
+v 0.002765 -0.627353 -0.381516
+v -0.032817 -0.630755 -0.465039
+v -0.049239 -0.623951 -0.491614
+v -0.036101 -0.636424 -0.465039
+v -0.045407 -0.619416 -0.491614
+v -0.009826 -0.653433 -0.423277
+v -0.014205 -0.651165 -0.423277
+v -0.020227 -0.647764 -0.446056
+v -0.024058 -0.645496 -0.442260
+v -0.032270 -0.638692 -0.468835
+v -0.045407 -0.627353 -0.495410
+v -0.058545 -0.613746 -0.518189
+v -0.062924 -0.610344 -0.514393
+v -0.006541 -0.648897 -0.423277
+v -0.016942 -0.643228 -0.446056
+v -0.028438 -0.634157 -0.468835
+v -0.041576 -0.621683 -0.491614
+v -0.054713 -0.609210 -0.518189
+v -0.020774 -0.640960 -0.442260
+v -0.010921 -0.645496 -0.423277
+v -0.059093 -0.605809 -0.514393
+v -0.101243 -0.515095 -1.376193
+v -0.105075 -0.519630 -1.376193
+v -0.100148 -0.523032 -1.376193
+v -0.096316 -0.518497 -1.376193
+v 0.015355 -0.653433 -0.423277
+v 0.037799 -0.638692 -0.468835
+v 0.019187 -0.650031 -0.423277
+v 0.041083 -0.635291 -0.465039
+v 0.064075 -0.613746 -0.518189
+v 0.067906 -0.609210 -0.514393
+v 0.006049 -0.644362 -0.389109
+v 0.003859 -0.639826 -0.392906
+v 0.015355 -0.645496 -0.423277
+v 0.105130 -0.515095 -1.376193
+v 0.110057 -0.518497 -1.376193
+v 0.106225 -0.523032 -1.376193
+v 0.000028 -0.633023 -0.373923
+v 0.001670 -0.647764 -0.385313
+v 0.000028 0.424924 0.518249
+v 0.001670 -0.627353 -0.381516
+v 0.010976 0.438531 0.525842
+v 0.006597 0.438531 0.529639
+v 0.004407 0.427192 0.514453
+v 0.004407 -0.630755 -0.377720
+v 0.008239 0.443067 0.522046
+v 0.001670 0.430594 0.510656
+v 0.004407 0.443067 0.525842
+v -0.003257 0.429460 0.514453
+v 0.014260 0.455540 0.537232
+v 0.018640 0.455540 0.533435
+v 0.026303 0.469147 0.548621
+v 0.030135 0.469147 0.544825
+v 0.037799 0.482754 0.560011
+v 0.042178 0.482754 0.556214
+v 0.047652 0.496361 0.571400
+v 0.032872 0.464612 0.548621
+v 0.020829 0.451005 0.537232
+v 0.052032 0.496361 0.567604
+v 0.044368 0.478219 0.560011
+v 0.040536 0.478219 0.563807
+v 0.028493 0.464612 0.552418
+v 0.016997 0.451005 0.541028
+v 0.054769 0.491826 0.571400
+v 0.050389 0.491826 0.575197
+v 0.057506 0.505433 0.582790
+v 0.054221 0.508834 0.578993
+v 0.062432 0.506567 0.582790
+v 0.059148 0.509969 0.578993
+v 0.061885 0.524710 0.586586
+v 0.065169 0.521308 0.590383
+v 0.060243 0.520174 0.594179
+v 0.055316 0.568932 0.616958
+v 0.044915 0.617691 0.647330
+v 0.058600 0.566665 0.620754
+v 0.053674 0.564397 0.620754
+v 0.039989 0.615423 0.651126
+v 0.028493 0.673253 0.673905
+v 0.023566 0.670985 0.677702
+v 0.014260 0.729949 0.700480
+v 0.021377 0.877359 0.784003
+v 0.007691 0.832001 0.757428
+v 0.004407 0.835403 0.753631
+v 0.002765 0.785511 0.727056
+v 0.005502 0.783243 0.730852
+v 0.010976 0.731083 0.696684
+v 0.025756 0.674387 0.670109
+v 0.042178 0.619959 0.643533
+v 0.009334 0.727681 0.704277
+v 0.001122 0.782109 0.734649
+v 0.037251 0.617691 0.643533
+v 0.006049 0.728815 0.700480
+v 0.003312 0.832001 0.761224
+v 0.024661 0.873957 0.787799
+v 0.173556 0.976009 0.787799
+v 0.171914 0.980545 0.784003
+v 0.120458 0.957867 0.802985
+v 0.020282 0.873957 0.791596
+v 0.068454 0.926117 0.802985
+v 0.071191 0.922715 0.799189
+v 0.121553 0.954465 0.795392
+v 0.068454 0.927251 0.795392
+v 0.119363 0.959001 0.795392
+v 0.173556 0.971473 0.784003
+v 0.224466 0.982813 0.772613
+v 0.222823 0.987349 0.768817
+v 0.268806 0.987349 0.753631
+v 0.269901 0.983947 0.757428
+v 0.223371 0.979411 0.768817
+v 0.171367 0.976009 0.780207
+v 0.118268 0.962403 0.799189
+v 0.306030 0.986215 0.742242
+v 0.306030 0.981679 0.746038
+v 0.268258 0.979411 0.753631
+v 0.221729 0.982813 0.765021
+v 0.305482 0.977143 0.742242
+v 0.304935 0.981679 0.738445
+v 0.267164 0.983947 0.749835
+v 0.331210 0.980545 0.738445
+v 0.331210 0.977143 0.742242
+v 0.331210 0.980545 0.746038
+v 0.059695 0.621093 0.613161
+v 0.036704 0.675521 0.681498
+v 0.054769 0.624494 0.609365
+v 0.040536 0.673253 0.685294
+v 0.026303 0.737886 0.723259
+v 0.015903 0.799117 0.734649
+v 0.021924 0.736753 0.727056
+v 0.018092 0.736753 0.723259
+v 0.012618 0.800251 0.730852
+v 0.020829 0.799117 0.730852
+v 0.082139 0.964671 0.734649
+v 0.088708 0.960135 0.738445
+v 0.060243 0.928385 0.734649
+v 0.067359 0.923849 0.734649
+v 0.022471 0.846743 0.730852
+v 0.025756 0.845609 0.734649
+v 0.030135 0.844475 0.734649
+v 0.063527 0.926117 0.738445
+v 0.084876 0.962403 0.742242
+v 0.108962 0.994153 0.742242
+v 0.106773 0.996421 0.738445
+v 0.137427 1.020233 0.746038
+v 0.140164 1.015697 0.742242
+v 0.172462 1.033839 0.742242
+v 0.112794 0.990751 0.738445
+v 0.287418 1.051983 0.772613
+v 0.288512 1.055383 0.768817
+v 0.209138 1.045179 0.749835
+v 0.210780 1.041777 0.746038
+v 0.170819 1.037241 0.746038
+v 0.135238 1.022501 0.738445
+v 0.209685 1.049715 0.746038
+v 0.169725 1.040643 0.742242
+v 0.030135 0.157320 -0.821907
+v 0.037799 0.194739 -0.795332
+v 0.037251 0.156186 -0.825704
+v 0.029588 0.194739 -0.791535
+v 0.044368 0.236694 -0.715606
+v 0.036157 0.235560 -0.715606
+v -0.004899 0.260506 -0.601712
+v 0.033967 0.262774 -0.639676
+v 0.037799 0.259372 -0.635880
+v -0.009278 0.263908 -0.605508
+v 0.000575 0.579138 0.446116
+v -0.001067 0.265042 -0.601712
+v 0.041083 0.263908 -0.635880
+v 0.041083 0.232158 -0.715606
+v 0.034514 0.191337 -0.791535
+v 0.034514 0.153918 -0.821907
+v 0.037251 0.588209 0.506860
+v 0.008239 0.578004 0.446116
+v 0.062432 0.599548 0.563807
+v 0.058053 0.604084 0.563807
+v 0.041631 0.583673 0.506860
+v 0.004407 0.574602 0.446116
+v 0.062980 0.625628 0.609365
+v 0.066264 0.604084 0.563807
+v 0.044915 0.587075 0.503064
+v -0.088653 -0.538907 -0.457446
+v -0.088653 -0.627353 -0.457446
+v -0.088653 -0.518497 -0.415684
+v 0.045463 -0.583130 -0.480225
+v 0.045463 -0.627353 -0.457446
+v -0.088653 -0.583130 -0.480225
+v -0.061830 -0.444792 -1.391379
+v -0.061830 -0.515095 -1.342025
+v -0.061830 -0.452729 -1.342025
+v -0.061830 -0.608076 -1.474902
+v -0.061830 -0.635290 -1.448327
+v -0.061830 -0.657969 -1.474902
+v -0.061830 -0.667040 -1.277485
+v -0.061830 -0.640960 -1.262299
+v -0.061830 -0.667040 -1.247113
+v -0.061830 -0.880217 -1.281281
+v -0.061830 -0.879083 -1.304060
+v -0.089748 -0.879083 -1.304060
+v -0.089748 -0.880217 -1.281281
+v -0.089748 -0.667040 -1.277485
+v -0.089748 -0.667040 -1.247113
+v -0.089748 -0.640960 -1.262299
+v -0.089748 -0.635290 -1.448327
+v -0.089748 -0.657969 -1.474902
+v -0.089748 -0.608076 -1.474902
+v -0.089748 -0.515095 -1.342025
+v -0.089748 -0.444792 -1.391379
+v -0.089748 -0.452729 -1.342025
+v 0.010428 0.655110 -0.465038
+v 0.053126 0.584807 -0.734588
+v 0.004954 0.661914 -0.468835
+v 0.058600 0.578004 -0.730792
+v 0.061338 0.585942 -0.780146
+v 0.052032 0.571200 -0.730792
+v 0.067359 0.580272 -0.783943
+v 0.061885 0.573468 -0.787739
+v 0.069001 0.612022 -0.821907
+v 0.073928 0.614290 -0.814314
+v 0.077760 0.708405 -0.844686
+v 0.082686 0.709539 -0.837093
+v 0.067359 0.617691 -0.806721
+v 0.076118 0.711807 -0.833297
+v -0.044313 0.584807 -0.734588
+v -0.052524 0.585942 -0.780146
+v -0.049787 0.578004 -0.730792
+v -0.058545 0.580272 -0.783943
+v -0.065114 0.614290 -0.814314
+v -0.058545 0.617691 -0.806721
+v 0.003859 0.661914 -0.468835
+v -0.001615 0.655110 -0.465038
+v 0.004407 0.648307 -0.465038
+v -0.043218 0.571200 -0.730792
+v -0.053071 0.573468 -0.787739
+v -0.060187 0.612022 -0.821907
+v -0.068946 0.708405 -0.844686
+v -0.073873 0.709539 -0.837093
+v -0.067304 0.711807 -0.833297
+v 0.065717 0.563263 -0.738385
+v 0.039441 0.660780 -0.726995
+v 0.038346 0.564397 -0.742181
+v 0.066812 0.659646 -0.723199
+v 0.077760 0.665316 -0.787739
+v 0.075570 0.566665 -0.795332
+v 0.048200 0.567799 -0.799128
+v 0.050937 0.666450 -0.791535
+v -0.057450 0.563263 -0.738385
+v -0.069493 0.665316 -0.787739
+v -0.067304 0.566665 -0.795332
+v -0.058545 0.659646 -0.723199
+v -0.031175 0.660780 -0.726995
+v -0.031722 0.574602 -0.749774
+v -0.039933 0.567799 -0.799128
+v -0.038838 0.576870 -0.791535
+v -0.039933 0.623361 -0.783943
+v -0.030080 0.564397 -0.742181
+v -0.057450 0.215149 0.681498
+v 0.004407 0.299059 0.871322
+v 0.004407 0.229890 0.673905
+v -0.057450 0.284318 0.878915
+v 0.004407 0.312667 1.057349
+v -0.057450 0.297925 1.064942
+v 0.004407 0.294524 1.137075
+v -0.057450 0.284318 1.144668
+v -0.025153 0.278649 1.175040
+v 0.033967 0.278649 1.175040
+v -0.024058 0.267310 1.167447
+v 0.066264 0.284318 1.144668
+v 0.066264 0.297925 1.064942
+v 0.066264 0.284318 0.878915
+v 0.066264 0.215149 0.681498
+v 0.058600 0.089284 0.510656
+v 0.066264 0.097222 0.503064
+v 0.058600 0.272979 0.878915
+v 0.059148 0.286586 1.064942
+v 0.004407 0.111963 0.495471
+v -0.057450 0.097222 0.503064
+v 0.004407 -0.049054 0.358797
+v 0.066264 -0.063795 0.366390
+v -0.057450 -0.063795 0.366390
+v -0.050334 -0.068331 0.377780
+v -0.049787 0.089284 0.510656
+v -0.049239 0.204944 0.689091
+v -0.050334 0.286586 1.064942
+v -0.057450 -0.148839 0.324629
+v 0.004407 -0.136366 0.320832
+v -0.024058 -0.174919 0.317036
+v 0.032872 -0.174919 0.317036
+v 0.066264 -0.148839 0.324629
+v -0.022964 -0.176053 0.328425
+v 0.031777 -0.176053 0.328425
+v 0.004407 -0.125026 0.339815
+v 0.059148 -0.068331 0.377780
+v 0.004407 -0.055857 0.370187
+v 0.004407 0.101757 0.506860
+v 0.058053 0.204944 0.689091
+v 0.004407 0.218551 0.681498
+v 0.062432 -0.152241 0.339815
+v 0.004407 0.286586 0.871322
+v 0.004407 0.287720 1.114296
+v 0.062432 0.271845 1.140872
+v 0.032872 0.267310 1.167447
+v 0.004407 0.300193 1.057349
+v -0.049787 0.272979 0.878915
+v -0.070588 -0.627353 -1.250910
+v -0.070588 -0.627353 -1.292671
+v -0.070588 -0.665906 -1.315450
+v -0.059640 -0.627353 -1.250910
+v -0.059640 -0.627353 -1.292671
+v -0.070588 -0.665906 -1.228131
+v -0.070588 -0.703326 -1.250910
+v -0.070588 -0.703326 -1.292671
+v -0.059640 -0.665906 -1.228131
+v -0.080989 -0.809914 -1.311653
+v -0.080989 -0.847333 -1.334432
+v -0.080989 -0.809914 -1.269892
+v -0.070041 -0.809914 -1.269892
+v -0.070041 -0.809914 -1.311653
+v -0.080989 -0.847333 -1.247113
+v -0.080989 -0.885887 -1.269892
+v -0.080989 -0.885887 -1.311653
+v -0.070041 -0.885887 -1.269892
+v -0.119855 -0.481077 -1.376193
+v -0.119855 -0.475408 -1.368600
+v -0.123687 -0.477676 -1.372397
+v -0.110549 -0.499220 -1.410362
+v -0.110549 -0.482211 -1.406565
+v -0.087011 -0.499220 -1.410362
+v -0.098506 -0.519630 -1.376193
+v -0.110549 -0.519630 -1.376193
+v -0.110549 -0.499220 -1.334432
+v -0.110549 -0.444792 -1.349618
+v -0.110549 -0.435720 -1.387583
+v -0.098506 -0.516229 -1.338228
+v -0.087011 -0.519630 -1.376193
+v -0.087011 -0.482211 -1.406565
+v -0.087011 -0.499220 -1.334432
+v -0.087011 -0.444792 -1.349618
+v 0.119363 -0.499220 -1.334432
+v 0.107320 -0.516229 -1.338228
+v 0.107320 -0.519630 -1.376193
+v 0.119363 -0.519630 -1.376193
+v 0.119363 -0.499220 -1.410362
+v 0.119363 -0.482211 -1.406565
+v 0.119363 -0.444792 -1.349618
+v 0.119363 -0.435720 -1.387583
+v 0.107320 -0.483345 -1.330635
+v -0.035007 -0.570657 -0.415684
+v -0.035007 0.602950 0.571400
+v -0.007636 -0.530970 -0.453649
+v -0.007636 0.639235 0.529639
+v 0.036157 0.602950 0.571400
+v 0.036157 -0.570657 -0.415684
+v -0.007636 0.566665 0.613161
+v -0.022416 0.952197 0.708074
+v -0.022416 0.970339 0.727056
+v -0.022416 0.977143 0.708074
+v -0.022416 0.970339 0.689091
+v -0.022416 0.952197 0.681498
+v 0.032325 0.935189 0.689091
+v 0.032325 0.952197 0.708074
+v 0.032325 0.927251 0.708074
+v 0.032325 0.935189 0.727056
+v 0.032325 0.952197 0.734649
+v -0.049239 0.141444 0.814375
+v -0.049239 0.133507 0.818171
+v -0.061282 0.141444 0.814375
+v -0.061282 0.133507 0.818171
+v -0.061282 0.150516 0.848543
+v -0.061282 0.157319 0.920676
+v -0.049239 0.166391 0.916880
+v -0.061282 0.166391 0.916880
+v -0.049239 0.157319 0.920676
+v 0.332305 0.980545 0.753631
+v 0.376645 0.974875 0.727056
+v 0.376645 0.991885 0.738445
+v 0.332305 0.963537 0.742242
+v 0.324094 1.042911 0.730852
+v 0.328473 1.016831 0.746038
+v 0.329021 1.044045 0.730852
+v 0.310409 1.070125 0.780207
+v 0.329021 1.020233 0.749835
+v 0.344348 1.061053 0.765021
+v 0.343801 1.039509 0.776410
+v 0.330116 1.046313 0.734649
+v 0.326831 1.041777 0.734649
+v 0.314788 1.064455 0.780207
+v 0.311504 1.064455 0.776410
+v 0.311504 1.050849 0.787799
+v 0.310409 1.049715 0.791596
+v 0.314788 1.051983 0.787799
+v 0.313693 1.070125 0.780207
+v 0.322999 1.019099 0.746038
+v 0.324642 1.022501 0.746038
+v 0.313693 1.050849 0.795392
+v 0.343801 1.075795 0.791596
+v 0.367887 1.063321 0.776410
+v 0.367339 1.073527 0.795392
+v 0.385951 1.067857 0.787799
+v 0.386499 1.059919 0.768817
+v 0.447809 1.067857 0.787799
+v 0.487770 1.074661 0.802985
+v 0.481748 1.080331 0.810578
+v 0.455472 1.062187 0.776410
+v 0.385951 1.046313 0.776410
+v 0.332305 1.012295 0.738445
+v 0.376645 1.012295 0.738445
+v 0.332305 1.029303 0.727056
+v 0.376645 1.029303 0.727056
+v 0.332305 1.034973 0.708074
+v 0.376645 1.034973 0.708074
+v 0.332305 1.029303 0.689091
+v 0.376645 1.029303 0.689091
+v 0.332305 1.012295 0.677702
+v 0.376645 1.012295 0.677702
+v 0.332305 0.991885 0.677702
+v 0.376645 0.991885 0.677702
+v 0.383762 1.022501 0.692888
+v 0.325736 1.022501 0.692888
+v 0.383762 1.010027 0.685295
+v 0.545795 1.022501 0.692888
+v 0.545795 1.010027 0.685295
+v 0.383762 0.994153 0.685295
+v 0.385951 1.056517 0.791596
+v 0.367339 1.059919 0.802985
+v 0.367887 1.047447 0.787799
+v 0.343801 1.057651 0.802985
+v 0.447809 1.056517 0.791596
+v 0.482843 1.071259 0.814375
+v 0.267711 1.048581 0.738445
+v 0.268258 1.027035 0.761224
+v 0.286870 1.070125 0.776410
+v 0.287418 1.050849 0.791596
+v 0.325736 0.994153 0.730852
+v 0.325736 1.010027 0.730852
+v 0.325736 0.991885 0.738445
+v 0.260047 0.991885 0.738445
+v 0.254026 0.991885 0.727056
+v 0.260047 0.974875 0.727056
+v 0.254026 1.005491 0.727056
+v 0.325736 0.974875 0.727056
+v 0.325736 0.969205 0.708074
+v 0.260047 0.969205 0.708074
+v 0.325736 0.981679 0.723259
+v 0.325736 0.977143 0.708074
+v 0.325736 0.974875 0.689091
+v 0.260047 0.974875 0.689091
+v 0.325736 0.991885 0.677702
+v 0.325736 1.010027 0.685295
+v 0.325736 0.994153 0.685295
+v 0.325736 1.012295 0.677702
+v 0.325736 1.034973 0.708074
+v 0.325736 1.027035 0.708074
+v 0.325736 1.029303 0.689091
+v 0.325736 1.022501 0.723259
+v 0.260047 1.034973 0.708074
+v 0.260047 1.029303 0.689091
+v 0.260047 1.012295 0.677702
+v 0.260047 0.991885 0.677702
+v 0.254026 1.005491 0.689091
+v 0.254026 1.015697 0.696684
+v 0.254026 1.020233 0.708074
+v 0.551816 0.982813 0.708074
+v 0.551816 0.996421 0.727056
+v 0.551816 0.986215 0.719463
+v 0.551816 1.020233 0.708074
+v 0.551816 1.016831 0.719463
+v 0.551816 1.007759 0.727056
+v 0.551816 0.986215 0.696684
+v 0.551816 0.996421 0.689091
+v 0.551816 1.016831 0.696684
+v 0.545795 1.027035 0.708074
+v 0.545795 1.022501 0.723259
+v 0.545795 1.010027 0.730852
+v 0.551816 1.007759 0.689091
+v 0.545795 0.981679 0.723259
+v 0.545795 0.981679 0.692888
+v 0.545795 0.994153 0.685295
+v -0.367832 0.974875 0.727056
+v -0.323491 0.974875 0.727056
+v -0.323491 0.963537 0.742242
+v -0.323491 0.980545 0.753631
+v -0.367832 0.974875 0.689091
+v -0.323491 0.969205 0.708074
+v -0.367832 0.969205 0.708074
+v -0.367832 0.991885 0.738445
+v -0.367832 1.012295 0.738445
+v -0.374948 0.994153 0.730852
+v -0.374948 1.010027 0.730852
+v -0.367832 1.012295 0.677702
+v -0.323491 0.991885 0.677702
+v -0.367832 0.991885 0.677702
+v -0.323491 1.012295 0.677702
+v -0.367832 1.029303 0.689091
+v -0.323491 1.029303 0.689091
+v -0.367832 1.034973 0.708074
+v -0.323491 1.034973 0.708074
+v -0.367832 1.029303 0.727056
+v -0.323491 1.029303 0.727056
+v -0.323491 1.012295 0.738445
+v -0.323491 0.991885 0.738445
+v -0.323491 0.974875 0.689091
+v -0.316923 0.981679 0.692888
+v -0.374948 1.027035 0.708074
+v -0.374948 1.010027 0.685295
+v -0.374948 0.994153 0.685295
+v -0.536981 1.010027 0.730852
+v -0.374948 1.022501 0.723259
+v -0.536981 1.022501 0.723259
+v 0.004407 0.114230 0.768817
+v 0.002217 0.111963 0.761224
+v 0.046010 -0.458399 0.989013
+v -0.358526 1.073527 0.795392
+v -0.377138 1.056517 0.791596
+v -0.358526 1.059919 0.802985
+v -0.359073 1.047447 0.787799
+v -0.334987 1.057651 0.802985
+v -0.334987 1.075795 0.791596
+v -0.304879 1.050849 0.795392
+v -0.334987 1.039509 0.776410
+v -0.320207 1.020233 0.749835
+v -0.305974 1.051983 0.787799
+v -0.304879 1.070125 0.780207
+v -0.335534 1.061053 0.765021
+v -0.359073 1.063321 0.776410
+v -0.377138 1.067857 0.787799
+v -0.321302 1.046313 0.734649
+v -0.305974 1.064455 0.780207
+v -0.302690 1.050849 0.787799
+v -0.302690 1.064455 0.776410
+v -0.377685 1.059919 0.768817
+v -0.438995 1.067857 0.787799
+v -0.318017 1.041777 0.734649
+v -0.315280 1.042911 0.730852
+v -0.315828 1.022501 0.746038
+v -0.314185 1.019099 0.746038
+v -0.319660 1.016831 0.746038
+v -0.320207 1.044045 0.730852
+v 0.048747 -0.456131 0.996606
+v 0.051484 -0.457265 0.989013
+v 0.006597 0.111963 0.761224
+v -0.446111 1.049715 0.784003
+v -0.478956 1.074661 0.802985
+v -0.446659 1.062187 0.776410
+v -0.474029 1.071259 0.814375
+v -0.478956 1.065589 0.806782
+v -0.472934 1.080331 0.810578
+v -0.377138 1.046313 0.776410
+v -0.438995 1.056517 0.791596
+v -0.278604 1.050849 0.791596
+v -0.301595 1.049715 0.791596
+v -0.259445 1.027035 0.761224
+v -0.301595 1.070125 0.780207
+v -0.278056 1.070125 0.776410
+v -0.258897 1.048581 0.738445
+v -0.245212 1.015697 0.719463
+v -0.251233 1.034973 0.708074
+v -0.245212 1.020233 0.708074
+v -0.251233 1.029303 0.689091
+v -0.316923 1.029303 0.689091
+v -0.316923 1.012295 0.677702
+v -0.316923 1.034973 0.708074
+v -0.251233 1.012295 0.677702
+v -0.316923 0.991885 0.677702
+v -0.251233 0.991885 0.677702
+v -0.245212 0.991885 0.689091
+v -0.251233 0.974875 0.689091
+v -0.316923 1.010027 0.685295
+v -0.316923 0.994153 0.685295
+v -0.316923 1.022501 0.692888
+v -0.316923 1.027035 0.708074
+v -0.316923 1.022501 0.723259
+v -0.245212 0.980545 0.719463
+v -0.251233 0.969205 0.708074
+v -0.245212 0.977143 0.708074
+v -0.251233 0.974875 0.727056
+v -0.316923 0.969205 0.708074
+v -0.251233 0.991885 0.738445
+v -0.316923 0.991885 0.738445
+v -0.316923 0.974875 0.727056
+v -0.316923 0.977143 0.708074
+v -0.543003 0.982813 0.708074
+v -0.543003 0.996421 0.689091
+v -0.543003 0.986215 0.696684
+v -0.543003 1.020233 0.708074
+v -0.543003 1.016831 0.696684
+v -0.543003 1.007759 0.689091
+v -0.543003 0.986215 0.719463
+v -0.543003 0.996421 0.727056
+v -0.543003 1.016831 0.719463
+v -0.536981 1.027035 0.708074
+v -0.543003 1.007759 0.727056
+v -0.536981 0.994153 0.685295
+v -0.536981 0.977143 0.708074
+v -0.144489 0.399978 0.639737
+v -0.102885 0.430594 0.643533
+v -0.048144 0.373898 0.563807
+v -0.027343 0.406782 0.575197
+v -0.043765 0.446469 0.685294
+v -0.024058 0.406782 0.575197
+v 0.015903 0.423791 0.700480
+v 0.052579 0.446469 0.685294
+v 0.004407 0.443067 0.673905
+v 0.052579 0.435130 0.734649
+v 0.111152 0.446469 0.685294
+v 0.118268 0.435130 0.734649
+v -0.007089 0.423791 0.700480
+v 0.015903 0.378434 0.719463
+v 0.052579 0.389773 0.749835
+v 0.118268 0.389773 0.749835
+v 0.135238 0.432862 0.727056
+v 0.146186 0.429460 0.715666
+v 0.153302 0.423791 0.700480
+v 0.146186 0.384103 0.734649
+v 0.153302 0.378434 0.719463
+v 0.153302 0.399978 0.639737
+v 0.153302 0.354622 0.654922
+v 0.135238 0.387505 0.742242
+v 0.111699 0.430594 0.643533
+v 0.056958 0.373898 0.563807
+v -0.144489 0.378434 0.719463
+v -0.144489 0.423791 0.700480
+v -0.102338 0.446469 0.685294
+v -0.043765 0.435130 0.734649
+v -0.007089 0.378434 0.719463
+v -0.126424 0.432862 0.727056
+v -0.109454 0.389773 0.749835
+v -0.109454 0.435130 0.734649
+v -0.137372 0.429460 0.715666
+v -0.051976 0.122168 -0.863669
+v -0.051976 0.167525 -0.821907
+v 0.073928 0.122168 -0.863669
+v 0.073928 0.167525 -0.821907
+v 0.004407 -0.106884 -0.677641
+v 0.066264 -0.127294 -0.681438
+v -0.057450 -0.127294 -0.681438
+v -0.023511 -0.148839 -0.670048
+v 0.032325 -0.148839 -0.670048
+v 0.050389 0.566665 0.616958
+v 0.056958 0.522442 0.590383
+v 0.004407 0.969205 0.696684
+v -0.093032 0.973741 0.708074
+v -0.093032 0.969205 0.719463
+v -0.093579 0.957867 0.727056
+v 0.101846 0.969205 0.696684
+v -0.093579 0.957867 0.689091
+v 0.004407 0.957867 0.689091
+v -0.002162 0.784377 0.727056
+v 0.020829 0.672119 0.673905
+v 0.063527 -0.605809 -0.514393
+v 0.036704 -0.630755 -0.465039
+v 0.059148 0.106294 -1.884921
+v 0.128669 -0.475408 -1.368600
+v 0.063527 0.104025 -1.888718
+v 0.132501 -0.477676 -1.372397
+v 0.059148 0.100624 -1.892514
+v 0.128669 -0.481077 -1.376193
+v 0.004407 0.224221 -0.689031
+v -0.017489 0.231024 -0.662455
+v 0.004407 0.572334 -0.791535
+v 0.026303 0.231024 -0.662455
+v 0.026303 0.582540 -0.764960
+v 0.070096 0.133507 0.818171
+v 0.070096 0.150516 0.848543
+v 0.070096 0.152784 0.859932
+v 0.070096 0.157319 0.920676
+v 0.070096 0.141444 0.814375
+v 0.058053 0.133507 0.818171
+v 0.058053 0.141444 0.814375
+v 0.058053 0.157319 0.920676
+v 0.058053 0.166391 0.916880
+v 0.070096 0.166391 0.916880
+v 0.088708 -0.437989 1.000402
+v 0.089803 -0.437989 1.057349
+v 0.113889 -0.434587 1.064942
+v 0.113341 -0.042251 0.806782
+v -0.037744 0.393175 0.757428
+v 0.085424 0.164123 0.840950
+v 0.088708 0.412451 0.742242
+v 0.115531 0.160721 0.833357
+v 0.115531 0.166391 0.848543
+v -0.106717 0.166391 0.848543
+v 0.004407 0.396576 0.582790
+v 0.004407 0.427192 0.673905
+v -0.013110 0.938591 0.719463
+v 0.004407 0.716342 0.529639
+v -0.013110 0.732217 0.525842
+v 0.066264 -0.024107 -2.010205
+v 0.030683 -0.037714 -2.021594
+v 0.004407 0.299060 -1.455919
+v -0.021321 -0.148839 -0.681438
+v -0.098506 -0.435720 -1.387583
+v -0.085916 -0.417578 -1.353414
+v -0.087011 -0.435720 -1.387583
+v -0.098506 -0.444792 -1.345821
+v 0.004407 0.310399 -0.711809
+v 0.012071 0.324006 -0.711809
+v 0.004407 -0.594470 -0.468835
+v 0.047105 -0.569523 -0.597915
+v 0.095824 -0.499220 -1.334432
+v 0.004407 -0.558184 -0.419481
+v 0.004407 -0.586532 -0.419481
+v 0.107320 -0.444792 -1.345821
+v 0.095824 -0.444792 -1.349618
+v 0.107320 -0.435720 -1.387583
+v 0.095824 -0.435720 -1.387583
+v -0.007636 0.624494 0.567604
+v -0.004352 0.255971 -0.666252
+v 0.078855 0.189069 0.844747
+v 0.058053 0.151650 0.856136
+v -0.049239 0.151650 0.856136
+v 0.176841 0.968071 0.696684
+v -0.221126 0.980545 0.696684
+v -0.245212 0.980545 0.696684
+v 0.004407 0.750359 0.548621
+v -0.025701 0.741288 0.522046
+v 0.023566 0.667583 0.761224
+v -0.072778 0.960135 0.746038
+v -0.118760 1.003223 0.742242
+v -0.289005 1.055383 0.768817
+v 0.022471 0.617691 0.765021
+v 0.027946 0.667583 0.768817
+v 0.031777 0.739020 0.772613
+v -0.287910 1.051983 0.772613
+v 0.008239 0.319470 0.795392
+v -0.071136 -0.875681 -1.239520
+v -0.071136 -0.451595 -0.411888
+v -0.071136 -0.415310 -1.391379
+v -0.076610 -0.445926 -0.411888
+v -0.299953 0.973741 0.738445
+v 0.017545 0.878493 0.791596
+v 0.000028 0.834269 0.757428
+v 0.065717 0.929519 0.802985
+v 0.331210 0.985081 0.742242
+v 0.044368 0.676655 0.685294
+v 0.289060 1.047447 0.768817
+v -0.088653 -0.648897 -0.415684
+v -0.088653 -0.627353 -0.370127
+v -0.088653 -0.538907 -0.370127
+v -0.088653 -0.583130 -0.347348
+v 0.045463 -0.627353 -0.370127
+v 0.045463 -0.648897 -0.415684
+v 0.045463 -0.583130 -0.347348
+v 0.045463 -0.538907 -0.457446
+v 0.045463 -0.538907 -0.370127
+v 0.045463 -0.518497 -0.415684
+v 0.048200 0.623361 -0.783943
+v 0.041083 0.619959 -0.745978
+v 0.039989 0.574602 -0.749774
+v 0.047105 0.576870 -0.791535
+v -0.042670 0.666450 -0.791535
+v -0.032817 0.619959 -0.745978
+v -0.053619 0.271845 1.140872
+v -0.053619 -0.152241 0.339815
+v -0.059640 -0.703326 -1.250910
+v -0.059640 -0.703326 -1.292671
+v -0.059640 -0.665906 -1.315450
+v -0.070041 -0.847333 -1.247113
+v -0.070041 -0.885887 -1.311653
+v -0.070041 -0.847333 -1.334432
+v -0.054713 0.104025 -1.888718
+v -0.050334 0.106294 -1.884921
+v -0.050334 0.100624 -1.892514
+v -0.046502 0.102892 -1.888718
+v -0.115476 -0.478809 -1.372397
+v 0.055316 0.102892 -1.888718
+v 0.095824 -0.519630 -1.376193
+v 0.095824 -0.499220 -1.410362
+v 0.095824 -0.482211 -1.406565
+v 0.004407 0.238962 -0.635880
+v -0.007636 -0.610344 -0.373923
+v -0.022416 0.952197 0.734649
+v -0.022416 0.935189 0.689091
+v -0.022416 0.927251 0.708074
+v -0.022416 0.935189 0.727056
+v 0.032325 0.970339 0.727056
+v 0.032325 0.977143 0.708074
+v 0.032325 0.970339 0.689091
+v 0.032325 0.952197 0.681498
+v -0.033364 0.144846 0.810578
+v -0.033364 0.128971 0.814375
+v -0.033364 0.155052 0.924473
+v -0.033364 0.170926 0.920676
+v 0.332305 0.974875 0.727056
+v 0.332305 0.991885 0.738445
+v 0.454925 1.049715 0.784003
+v 0.487770 1.065589 0.806782
+v 0.376645 0.969205 0.708074
+v 0.383762 0.981679 0.692888
+v 0.383762 0.977143 0.708074
+v 0.376645 0.974875 0.689091
+v 0.332305 0.969205 0.708074
+v 0.383762 0.981679 0.723259
+v 0.383762 0.994153 0.730852
+v 0.383762 1.010027 0.730852
+v 0.332305 0.974875 0.689091
+v 0.325736 0.981679 0.692888
+v 0.383762 1.022501 0.723259
+v 0.383762 1.027035 0.708074
+v 0.545795 0.977143 0.708074
+v 0.545795 0.994153 0.730852
+v -0.316923 0.981679 0.723259
+v -0.374948 0.981679 0.692888
+v -0.374948 0.977143 0.708074
+v -0.374948 0.981679 0.723259
+v -0.316923 1.010027 0.730852
+v -0.316923 0.994153 0.730852
+v -0.374948 1.022501 0.692888
+v -0.536981 0.981679 0.692888
+v -0.536981 0.981679 0.723259
+v -0.536981 0.994153 0.730852
+v -0.536981 1.022501 0.692888
+v -0.536981 1.010027 0.685295
+v -0.316923 0.974875 0.689091
+v 0.004407 0.373898 0.563807
+v -0.144489 0.354622 0.654922
+v -0.048144 0.328541 0.582790
+v 0.004407 0.328541 0.582790
+v 0.056958 0.328541 0.582790
+v -0.043765 0.389773 0.749835
+v -0.137372 0.384103 0.734649
+v -0.126424 0.387505 0.742242
+v 0.124290 -0.478809 -1.372397
+v -0.017489 0.582540 -0.764960
+v 0.004407 0.593879 -0.738385
+v 0.042178 0.155052 0.924473
+v 0.042178 0.128971 0.814375
+v 0.042178 0.144846 0.810578
+v 0.042178 0.170926 0.920676
+# 1445 vertices, 0 vertices normals
+
+f 1 2 3
+f 4 5 6
+f 6 5 7
+f 8 6 9
+f 4 6 8
+f 10 4 8
+f 11 4 10
+f 4 11 5
+f 5 11 12
+f 6 13 9
+f 13 6 14
+f 14 6 7
+f 15 14 7
+f 5 15 7
+f 16 14 15
+f 17 18 19
+f 20 18 17
+f 20 17 21
+f 21 17 22
+f 17 19 22
+f 22 19 23
+f 24 18 20
+f 24 25 18
+f 18 25 26
+f 27 28 29
+f 30 28 27
+f 31 30 27
+f 32 30 31
+f 31 33 34
+f 27 33 31
+f 27 35 33
+f 29 35 27
+f 29 36 35
+f 28 30 9
+f 9 30 8
+f 30 32 8
+f 8 32 10
+f 10 32 37
+f 37 11 10
+f 38 11 37
+f 11 38 12
+f 12 38 39
+f 40 12 39
+f 41 40 39
+f 42 40 41
+f 38 41 39
+f 43 41 38
+f 43 38 44
+f 44 38 37
+f 45 43 44
+f 44 46 45
+f 37 46 44
+f 47 46 37
+f 37 32 47
+f 47 32 48
+f 48 32 31
+f 48 31 49
+f 49 31 34
+f 50 48 49
+f 51 48 50
+f 51 47 48
+f 46 47 51
+f 52 46 51
+f 53 46 52
+f 45 46 53
+f 54 55 56
+f 56 57 54
+f 58 57 56
+f 59 55 54
+f 60 55 61
+f 62 63 64
+f 65 62 66
+f 65 66 67
+f 67 66 68
+f 69 68 66
+f 69 66 70
+f 70 66 62
+f 70 62 71
+f 71 62 64
+f 71 64 72
+f 72 64 73
+f 63 73 64
+f 74 73 63
+f 63 75 74
+f 76 71 77
+f 77 71 72
+f 77 72 78
+f 78 72 79
+f 72 73 79
+f 79 73 80
+f 74 75 81
+f 81 75 82
+f 82 75 83
+f 83 84 82
+f 85 84 83
+f 83 75 85
+f 85 75 86
+f 63 86 75
+f 87 86 63
+f 87 63 62
+f 87 62 65
+f 67 88 65
+f 65 88 89
+f 65 89 87
+f 87 89 86
+f 90 86 89
+f 85 86 90
+f 90 88 91
+f 89 88 90
+f 92 84 85
+f 91 93 90
+f 67 94 88
+f 95 94 67
+f 96 68 69
+f 96 69 97
+f 97 69 98
+f 69 70 98
+f 98 70 99
+f 99 70 76
+f 76 70 71
+f 100 101 102
+f 103 104 105
+f 106 105 104
+f 107 105 106
+f 107 108 105
+f 109 110 102
+f 111 110 109
+f 109 112 111
+f 113 114 115
+f 116 117 118
+f 119 120 121
+f 122 123 124
+f 125 124 126
+f 126 124 123
+f 126 123 127
+f 127 123 128
+f 129 130 131
+f 131 130 132
+f 128 131 132
+f 132 133 128
+f 128 133 127
+f 134 127 133
+f 135 127 134
+f 135 136 127
+f 127 136 126
+f 136 137 126
+f 138 139 134
+f 140 141 142
+f 130 141 140
+f 140 132 130
+f 133 132 140
+f 140 134 133
+f 138 134 140
+f 140 143 138
+f 142 143 140
+f 144 143 145
+f 146 144 145
+f 147 148 149
+f 150 151 152
+f 153 150 152
+f 153 152 154
+f 148 152 155
+f 149 148 155
+f 151 149 155
+f 152 151 155
+f 156 157 158
+f 158 157 159
+f 158 159 160
+f 160 159 161
+f 162 160 161
+f 163 164 157
+f 157 164 159
+f 162 165 166
+f 167 160 162
+f 168 169 170
+f 169 171 170
+f 172 173 169
+f 172 169 168
+f 168 174 172
+f 175 174 168
+f 174 176 177
+f 174 177 172
+f 172 177 178
+f 178 173 172
+f 178 179 173
+f 177 180 178
+f 178 180 181
+f 181 179 178
+f 182 183 184
+f 183 182 185
+f 185 182 186
+f 183 185 187
+f 187 185 188
+f 189 187 190
+f 189 191 187
+f 187 191 183
+f 192 193 194
+f 194 193 195
+f 194 195 196
+f 196 195 197
+f 197 195 198
+f 198 195 199
+f 198 199 200
+f 199 201 200
+f 195 193 199
+f 199 193 201
+f 202 203 192
+f 204 205 184
+f 206 207 208
+f 209 210 211
+f 212 209 211
+f 213 209 212
+f 213 214 209
+f 215 214 213
+f 215 216 214
+f 217 216 215
+f 214 218 209
+f 209 218 210
+f 218 219 210
+f 216 208 214
+f 214 208 218
+f 208 207 218
+f 207 219 218
+f 220 221 222
+f 223 221 220
+f 224 223 220
+f 225 223 224
+f 226 227 228
+f 229 226 230
+f 231 226 229
+f 231 232 226
+f 226 232 227
+f 232 233 227
+f 227 233 234
+f 234 233 235
+f 235 233 236
+f 236 233 237
+f 238 236 237
+f 237 233 239
+f 239 233 240
+f 240 233 232
+f 241 242 238
+f 238 242 243
+f 243 236 238
+f 243 244 236
+f 236 244 235
+f 242 244 243
+f 242 245 246
+f 246 244 242
+f 247 248 249
+f 249 248 250
+f 249 250 251
+f 251 250 252
+f 251 252 253
+f 253 252 254
+f 255 256 257
+f 257 256 258
+f 259 258 256
+f 260 261 258
+f 260 258 259
+f 262 263 264
+f 264 263 265
+f 266 267 260
+f 267 261 260
+f 267 268 261
+f 269 270 271
+f 272 273 268
+f 272 268 267
+f 274 272 267
+f 274 267 266
+f 266 275 274
+f 265 275 266
+f 276 277 278
+f 276 279 277
+f 276 280 279
+f 279 280 275
+f 275 280 281
+f 275 281 274
+f 274 281 282
+f 282 272 274
+f 282 283 272
+f 283 273 272
+f 265 279 275
+f 263 279 265
+f 277 279 263
+f 284 285 286
+f 287 284 286
+f 288 284 287
+f 289 288 287
+f 290 288 289
+f 290 289 291
+f 278 292 291
+f 277 292 278
+f 293 294 295
+f 294 293 285
+f 296 294 285
+f 296 285 284
+f 295 294 297
+f 294 298 297
+f 298 294 296
+f 299 300 301
+f 302 299 303
+f 299 301 303
+f 303 301 304
+f 302 305 306
+f 303 305 302
+f 300 307 301
+f 300 308 307
+f 309 308 300
+f 293 310 311
+f 285 293 311
+f 285 311 286
+f 312 313 314
+f 312 310 313
+f 315 310 312
+f 311 310 315
+f 311 315 316
+f 286 311 316
+f 317 286 316
+f 287 286 317
+f 318 287 317
+f 289 287 318
+f 319 312 314
+f 320 312 319
+f 320 315 312
+f 321 315 320
+f 316 315 321
+f 322 316 321
+f 317 316 322
+f 323 317 322
+f 318 317 323
+f 318 323 324
+f 321 320 322
+f 325 326 327
+f 319 326 325
+f 328 319 325
+f 320 319 328
+f 322 320 328
+f 322 328 323
+f 323 328 329
+f 328 325 329
+f 329 325 330
+f 325 327 330
+f 330 327 331
+f 327 332 331
+f 327 333 332
+f 326 333 327
+f 326 334 333
+f 326 314 334
+f 319 314 326
+f 331 332 335
+f 332 336 335
+f 332 302 336
+f 333 302 332
+f 333 299 302
+f 333 334 299
+f 334 300 299
+f 334 309 300
+f 314 309 334
+f 314 313 309
+f 337 338 339
+f 340 338 337
+f 338 340 341
+f 340 335 341
+f 341 335 342
+f 335 336 342
+f 342 336 343
+f 343 336 344
+f 336 302 344
+f 344 302 306
+f 342 343 341
+f 341 343 345
+f 346 341 345
+f 341 346 338
+f 338 346 347
+f 347 348 338
+f 349 347 346
+f 350 347 351
+f 348 347 350
+f 352 348 350
+f 353 348 352
+f 353 338 348
+f 339 338 353
+f 351 354 350
+f 350 354 355
+f 350 355 352
+f 356 339 357
+f 339 353 357
+f 357 353 358
+f 358 353 352
+f 352 359 358
+f 352 355 359
+f 355 360 359
+f 355 361 360
+f 354 361 355
+f 362 356 363
+f 363 356 357
+f 363 357 364
+f 364 357 358
+f 358 365 364
+f 358 359 365
+f 362 366 367
+f 363 366 362
+f 366 363 368
+f 368 363 364
+f 364 369 368
+f 364 365 369
+f 365 370 369
+f 365 371 370
+f 359 371 365
+f 359 360 371
+f 369 370 372
+f 368 369 373
+f 369 372 373
+f 373 372 374
+f 281 373 282
+f 282 373 374
+f 374 283 282
+f 374 372 283
+f 283 372 375
+f 372 370 375
+f 375 370 376
+f 370 371 376
+f 376 371 377
+f 371 360 377
+f 283 375 273
+f 273 375 271
+f 375 376 271
+f 271 376 269
+f 376 377 269
+f 269 377 378
+f 377 379 378
+f 378 379 380
+f 379 381 380
+f 380 381 382
+f 377 360 379
+f 360 361 379
+f 379 361 381
+f 383 384 382
+f 382 384 380
+f 385 386 387
+f 388 386 389
+f 387 390 385
+f 391 392 393
+f 391 393 394
+f 394 393 395
+f 396 394 395
+f 396 395 397
+f 396 397 398
+f 398 397 399
+f 393 400 395
+f 395 400 401
+f 395 401 397
+f 402 403 404
+f 402 404 392
+f 392 404 405
+f 393 392 405
+f 393 405 400
+f 405 404 406
+f 405 406 407
+f 400 405 407
+f 407 406 408
+f 409 410 411
+f 412 413 414
+f 415 412 414
+f 416 417 418
+f 419 417 416
+f 419 416 420
+f 416 418 421
+f 422 423 424
+f 423 425 424
+f 426 427 428
+f 429 422 427
+f 429 423 422
+f 429 430 423
+f 430 420 423
+f 423 420 425
+f 420 416 425
+f 431 430 429
+f 432 433 434
+f 432 435 433
+f 434 433 436
+f 437 438 439
+f 437 439 440
+f 440 439 441
+f 440 441 442
+f 442 441 443
+f 441 444 443
+f 445 446 447
+f 446 448 447
+f 449 450 451
+f 449 445 450
+f 452 445 449
+f 452 446 445
+f 452 453 446
+f 454 455 456
+f 455 451 456
+f 457 451 455
+f 457 449 451
+f 458 449 457
+f 454 459 460
+f 456 459 454
+f 456 461 459
+f 451 461 456
+f 451 450 461
+f 439 438 462
+f 438 463 462
+f 463 464 465
+f 466 463 467
+f 462 463 466
+f 468 469 413
+f 468 470 469
+f 471 472 473
+f 474 475 472
+f 472 475 473
+f 473 475 476
+f 473 476 471
+f 471 476 477
+f 477 476 478
+f 478 476 479
+f 478 479 480
+f 480 479 481
+f 480 481 482
+f 482 481 483
+f 483 484 482
+f 485 484 486
+f 487 480 482
+f 488 477 478
+f 489 472 471
+f 489 490 472
+f 491 490 489
+f 492 490 493
+f 493 490 491
+f 492 494 490
+f 495 494 492
+f 493 495 492
+f 496 495 493
+f 497 498 499
+f 499 498 500
+f 499 500 496
+f 496 500 495
+f 501 502 503
+f 503 502 504
+f 504 505 503
+f 503 505 498
+f 500 506 495
+f 506 494 495
+f 507 508 509
+f 509 508 510
+f 508 511 510
+f 510 511 512
+f 511 501 512
+f 512 501 513
+f 501 503 513
+f 513 503 514
+f 503 497 514
+f 498 497 503
+f 515 497 499
+f 512 513 516
+f 517 512 516
+f 510 512 517
+f 518 510 517
+f 509 510 518
+f 476 475 519
+f 479 520 481
+f 521 522 523
+f 522 524 523
+f 522 525 524
+f 525 526 524
+f 524 526 527
+f 526 528 527
+f 527 528 529
+f 528 530 529
+f 529 530 531
+f 530 532 531
+f 529 531 533
+f 534 529 533
+f 527 529 534
+f 535 527 534
+f 524 527 535
+f 523 524 535
+f 523 536 521
+f 534 537 535
+f 534 538 537
+f 533 538 534
+f 533 539 538
+f 540 539 533
+f 540 541 539
+f 542 543 544
+f 543 545 544
+f 521 536 546
+f 547 522 521
+f 547 521 548
+f 548 521 549
+f 548 549 550
+f 550 549 551
+f 550 551 552
+f 552 551 545
+f 552 545 553
+f 553 545 543
+f 553 543 554
+f 555 550 552
+f 555 552 556
+f 556 552 553
+f 556 553 557
+f 557 553 554
+f 557 554 558
+f 554 543 559
+f 554 559 560
+f 558 554 560
+f 558 560 561
+f 562 558 561
+f 561 560 563
+f 563 560 564
+f 564 560 565
+f 560 559 565
+f 566 561 567
+f 567 561 563
+f 567 563 568
+f 568 563 564
+f 565 559 569
+f 569 559 542
+f 559 543 542
+f 570 571 572
+f 572 573 570
+f 573 566 570
+f 570 566 567
+f 567 568 570
+f 570 568 571
+f 568 574 571
+f 571 574 575
+f 571 575 576
+f 576 575 577
+f 572 571 576
+f 576 577 578
+f 579 576 578
+f 572 576 579
+f 579 580 572
+f 580 573 572
+f 581 578 582
+f 579 578 581
+f 581 583 579
+f 583 580 579
+f 584 585 583
+f 584 583 581
+f 586 584 587
+f 587 584 581
+f 581 582 587
+f 587 582 588
+f 589 585 584
+f 586 589 584
+f 590 586 591
+f 586 587 591
+f 591 587 592
+f 592 587 593
+f 593 587 588
+f 556 594 555
+f 594 595 555
+f 555 595 596
+f 595 597 596
+f 596 597 598
+f 599 600 547
+f 599 547 598
+f 598 547 548
+f 598 548 596
+f 596 548 550
+f 596 550 555
+f 601 526 525
+f 600 525 522
+f 547 600 522
+f 602 603 604
+f 605 603 602
+f 605 602 606
+f 531 532 607
+f 532 606 607
+f 607 606 608
+f 606 602 608
+f 608 602 609
+f 610 608 609
+f 607 608 610
+f 540 607 610
+f 531 607 540
+f 533 531 540
+f 610 541 540
+f 610 611 541
+f 609 611 610
+f 609 612 611
+f 609 602 612
+f 602 613 612
+f 604 613 602
+f 604 614 613
+f 603 614 604
+f 615 614 603
+f 616 617 618
+f 613 617 616
+f 613 616 612
+f 612 616 619
+f 611 612 619
+f 620 621 622
+f 623 621 620
+f 615 624 614
+f 625 624 615
+f 625 626 624
+f 627 626 625
+f 627 628 626
+f 622 628 627
+f 622 629 628
+f 621 629 622
+f 621 630 629
+f 631 630 621
+f 613 614 617
+f 614 624 617
+f 617 624 632
+f 624 626 632
+f 632 626 633
+f 626 628 633
+f 633 628 634
+f 628 629 634
+f 634 629 635
+f 629 630 635
+f 635 630 636
+f 633 634 637
+f 638 633 637
+f 632 633 638
+f 618 632 638
+f 617 632 618
+f 623 631 621
+f 639 631 623
+f 639 640 631
+f 631 640 641
+f 631 641 630
+f 630 641 642
+f 630 642 636
+f 636 642 643
+f 644 645 646
+f 646 645 647
+f 645 648 647
+f 647 648 649
+f 650 646 651
+f 651 646 652
+f 646 647 652
+f 653 649 654
+f 649 648 654
+f 654 648 655
+f 650 656 657
+f 658 659 656
+f 657 644 650
+f 650 644 646
+f 660 661 662
+f 662 661 658
+f 658 656 662
+f 662 656 663
+f 663 656 650
+f 651 663 650
+f 664 662 665
+f 666 665 667
+f 664 665 666
+f 668 664 666
+f 669 664 668
+f 670 669 668
+f 671 669 670
+f 672 671 670
+f 673 671 672
+f 674 673 672
+f 673 675 671
+f 675 676 671
+f 671 676 669
+f 676 660 669
+f 669 660 664
+f 660 662 664
+f 677 673 674
+f 677 678 673
+f 678 675 673
+f 678 679 675
+f 675 679 680
+f 675 680 676
+f 676 680 681
+f 676 681 660
+f 660 681 661
+f 682 678 677
+f 682 683 678
+f 678 683 679
+f 684 685 683
+f 682 684 683
+f 686 684 682
+f 686 682 687
+f 688 686 687
+f 689 686 688
+f 689 684 686
+f 690 684 689
+f 691 692 693
+f 691 693 688
+f 688 693 689
+f 693 690 689
+f 694 690 693
+f 692 694 693
+f 695 694 692
+f 696 695 692
+f 697 695 696
+f 698 697 696
+f 699 700 701
+f 701 700 702
+f 702 700 703
+f 702 703 704
+f 704 703 698
+f 704 698 705
+f 705 698 696
+f 705 696 706
+f 706 696 692
+f 706 692 691
+f 707 697 698
+f 703 707 698
+f 708 707 703
+f 700 708 703
+f 697 709 695
+f 708 710 707
+f 711 708 700
+f 712 711 700
+f 712 700 699
+f 713 714 715
+f 716 711 712
+f 712 717 716
+f 718 717 712
+f 718 715 717
+f 719 715 718
+f 719 713 715
+f 699 718 712
+f 720 718 699
+f 720 719 718
+f 721 719 720
+f 721 722 719
+f 722 713 719
+f 722 723 713
+f 723 724 713
+f 713 724 714
+f 725 724 726
+f 726 724 723
+f 727 726 723
+f 727 723 722
+f 728 727 722
+f 728 722 721
+f 721 720 729
+f 730 725 731
+f 731 725 726
+f 732 731 726
+f 732 726 727
+f 733 732 727
+f 733 727 728
+f 734 731 732
+f 735 734 736
+f 736 734 732
+f 736 732 733
+f 737 734 735
+f 738 734 737
+f 738 731 734
+f 739 731 738
+f 740 741 742
+f 743 741 740
+f 744 745 746
+f 746 743 744
+f 746 747 743
+f 743 747 741
+f 748 749 747
+f 748 747 745
+f 745 747 746
+f 750 751 752
+f 752 751 753
+f 754 748 755
+f 755 748 745
+f 754 755 752
+f 755 756 757
+f 752 755 757
+f 758 752 757
+f 750 752 758
+f 759 750 758
+f 760 750 759
+f 761 760 759
+f 761 759 762
+f 763 761 762
+f 762 759 764
+f 759 758 764
+f 765 766 767
+f 768 767 763
+f 763 767 769
+f 769 761 763
+f 769 770 761
+f 770 760 761
+f 767 766 771
+f 772 770 769
+f 767 772 769
+f 771 772 767
+f 773 774 775
+f 776 774 773
+f 776 777 774
+f 778 777 776
+f 779 780 781
+f 782 780 779
+f 780 777 778
+f 779 783 782
+f 783 784 782
+f 782 784 780
+f 780 784 785
+f 785 777 780
+f 777 786 774
+f 774 786 787
+f 774 787 775
+f 775 787 788
+f 789 790 783
+f 790 784 783
+f 791 792 793
+f 793 792 789
+f 793 789 794
+f 794 789 783
+f 742 792 740
+f 740 792 791
+f 740 791 795
+f 795 791 796
+f 796 791 797
+f 797 791 793
+f 794 783 779
+f 798 799 800
+f 801 802 803
+f 804 805 806
+f 804 807 805
+f 807 808 805
+f 809 808 807
+f 809 810 808
+f 810 811 808
+f 810 812 811
+f 812 810 813
+f 810 814 813
+f 815 816 817
+f 817 816 818
+f 817 818 819
+f 819 820 817
+f 817 820 821
+f 820 822 821
+f 823 822 820
+f 824 822 823
+f 823 825 824
+f 826 827 828
+f 827 829 830
+f 829 827 826
+f 829 831 832
+f 832 831 833
+f 833 834 832
+f 832 834 835
+f 834 836 835
+f 835 836 837
+f 835 837 838
+f 838 837 839
+f 830 829 832
+f 832 835 830
+f 830 835 838
+f 840 841 842
+f 842 841 843
+f 841 844 843
+f 845 844 841
+f 846 840 847
+f 847 840 842
+f 847 842 848
+f 848 842 849
+f 842 843 849
+f 849 843 850
+f 843 851 850
+f 844 851 843
+f 851 844 852
+f 852 844 853
+f 844 845 853
+f 853 845 854
+f 855 856 857
+f 858 856 855
+f 855 859 858
+f 860 859 855
+f 860 861 859
+f 859 861 862
+f 863 864 865
+f 866 864 863
+f 866 863 867
+f 868 869 870
+f 869 871 870
+f 863 865 872
+f 873 874 875
+f 876 874 873
+f 876 877 874
+f 878 877 876
+f 877 878 879
+f 879 878 880
+f 879 880 881
+f 879 881 882
+f 880 883 881
+f 882 884 879
+f 884 885 879
+f 879 885 877
+f 886 877 885
+f 887 888 889
+f 890 887 886
+f 890 886 891
+f 891 886 885
+f 889 892 887
+f 874 877 886
+f 887 874 886
+f 875 874 887
+f 887 892 875
+f 875 892 873
+f 873 892 893
+f 892 894 893
+f 889 894 892
+f 895 894 889
+f 893 894 896
+f 897 893 896
+f 898 893 897
+f 898 873 893
+f 899 873 898
+f 876 900 878
+f 901 896 902
+f 903 901 902
+f 902 904 903
+f 902 905 904
+f 904 906 903
+f 907 906 904
+f 902 895 905
+f 894 895 902
+f 902 896 894
+f 908 909 910
+f 911 912 913
+f 914 909 908
+f 913 912 915
+f 916 917 918
+f 915 919 920
+f 921 922 923
+f 924 925 921
+f 926 924 921
+f 921 927 926
+f 923 927 921
+f 923 928 927
+f 929 924 926
+f 927 929 926
+f 921 925 922
+f 930 931 932
+f 933 934 932
+f 935 933 932
+f 935 932 936
+f 932 931 936
+f 931 937 936
+f 937 938 936
+f 932 934 930
+f 939 940 941
+f 942 943 944
+f 942 944 945
+f 946 942 945
+f 945 947 946
+f 943 946 947
+f 948 943 947
+f 949 943 948
+f 947 945 950
+f 946 943 942
+f 951 952 953
+f 952 954 953
+f 955 956 957
+f 958 957 959
+f 957 958 955
+f 955 958 960
+f 960 961 955
+f 962 961 960
+f 958 959 960
+f 955 961 963
+f 964 965 966
+f 966 965 967
+f 968 966 967
+f 969 966 968
+f 970 969 968
+f 971 972 973
+f 973 974 971
+f 971 974 975
+f 976 977 978
+f 978 977 979
+f 979 977 980
+f 981 982 983
+f 983 982 984
+f 984 985 983
+f 986 987 988
+f 989 987 986
+f 990 991 992
+f 993 991 990
+f 994 995 996
+f 994 996 997
+f 998 999 1000
+f 1001 999 998
+f 1001 998 1002
+f 1003 1001 1002
+f 1003 1002 994
+f 994 1004 1003
+f 997 1004 994
+f 1004 997 1005
+f 1005 997 1006
+f 1004 1005 1003
+f 1003 1005 1007
+f 1007 1008 1003
+f 1008 1001 1003
+f 1001 1008 999
+f 1005 1009 1010
+f 1010 1007 1005
+f 1011 1007 1010
+f 1011 1008 1007
+f 1008 1011 1012
+f 999 1008 1012
+f 999 1012 1013
+f 1013 1012 1014
+f 1015 1013 1014
+f 1016 1013 1015
+f 1017 1016 1015
+f 1018 1017 1019
+f 1020 1017 1018
+f 1020 1016 1017
+f 1021 1013 1016
+f 1013 1000 999
+f 1022 1023 1024
+f 1024 1023 1025
+f 1024 1025 1026
+f 1026 1025 1027
+f 1026 1027 1028
+f 1028 1027 1029
+f 1028 1029 1030
+f 1030 1029 1031
+f 1030 1031 1032
+f 1032 1031 1033
+f 1029 1034 1031
+f 1028 1035 1026
+f 1036 1037 1038
+f 1036 1038 1039
+f 1040 1014 1041
+f 1041 1042 1040
+f 1041 1043 1042
+f 1014 1043 1041
+f 1012 1043 1014
+f 1012 1011 1043
+f 1015 1014 1040
+f 1015 1040 1017
+f 1017 1040 1044
+f 1017 1044 1019
+f 1019 1044 1045
+f 1046 1047 1048
+f 1048 1047 1049
+f 1050 1051 1052
+f 1053 1054 1055
+f 1053 1056 1054
+f 1053 1057 1052
+f 1055 1057 1053
+f 1055 1058 1057
+f 1059 1058 1055
+f 1052 1060 1050
+f 1057 1060 1052
+f 1057 1061 1060
+f 1058 1061 1057
+f 1062 1058 1063
+f 1063 1058 1059
+f 1064 1065 1066
+f 1067 1065 1064
+f 1068 1069 1070
+f 1068 1071 1069
+f 1046 1068 1072
+f 1072 1068 1073
+f 1073 1068 1070
+f 1070 1067 1073
+f 1073 1067 1074
+f 1067 1064 1074
+f 1074 1064 1075
+f 1075 1076 1074
+f 1076 1077 1074
+f 1074 1077 1073
+f 1077 1078 1073
+f 1073 1078 1072
+f 1079 1080 1081
+f 1079 1082 1083
+f 1079 1083 1080
+f 1080 1083 1084
+f 1079 1085 1086
+f 1079 1086 1087
+f 1087 1082 1079
+f 1082 1087 1088
+f 1089 1082 1088
+f 1083 1082 1089
+f 1090 1083 1089
+f 1084 1083 1090
+f 1087 1086 1091
+f 1081 1080 1092
+f 1085 1079 1093
+f 1094 1085 1093
+f 1086 1085 1094
+f 1095 1096 1097
+f 1097 1098 1095
+f 1099 1100 1101
+f 1102 1103 1104
+f 1104 1103 1105
+f 1106 1107 1108
+f 1109 1107 1106
+f 1110 1109 1106
+f 1111 1109 1110
+f 1112 1111 1110
+f 1113 1111 1112
+f 1114 1113 1112
+f 1115 1113 1114
+f 1103 1115 1114
+f 1116 1115 1103
+f 1102 1116 1103
+f 1117 1116 1102
+f 1107 1118 1108
+f 1118 1107 1119
+f 1103 1114 1105
+f 1112 1110 1120
+f 1106 1108 1121
+f 1121 1108 1122
+f 1123 1124 1125
+f 1126 1127 1128
+f 1129 1130 1131
+f 1130 1132 1131
+f 1131 1132 1133
+f 1131 1133 1129
+f 1129 1133 1134
+f 1135 1134 1133
+f 1133 1136 1135
+f 1135 1136 1137
+f 1133 1132 1136
+f 1138 1139 1135
+f 1139 1134 1135
+f 1139 1140 1134
+f 1141 1134 1140
+f 1129 1134 1141
+f 1141 1142 1129
+f 1143 1140 1139
+f 1144 1143 1139
+f 1144 1139 1138
+f 1145 1144 1138
+f 1146 1144 1145
+f 1147 1148 1142
+f 1147 1142 1141
+f 1149 1143 1144
+f 1150 1149 1144
+f 1144 1146 1150
+f 1151 1149 1152
+f 1152 1149 1150
+f 1152 1150 1153
+f 1153 1150 1154
+f 1155 1156 1157
+f 1158 1159 1160
+f 1161 1159 1162
+f 1163 1159 1161
+f 1163 1148 1159
+f 1159 1148 1160
+f 1160 1148 1147
+f 1160 1147 1158
+f 1158 1147 1164
+f 1147 1141 1164
+f 1142 1130 1129
+f 1148 1130 1142
+f 1165 1130 1148
+f 1163 1165 1148
+f 1166 1167 1168
+f 1166 1169 1167
+f 1170 1169 1166
+f 1171 1172 1173
+f 1173 1172 1174
+f 1173 1174 1175
+f 1176 1175 1177
+f 1178 1175 1176
+f 1173 1175 1178
+f 1173 1178 1171
+f 1170 1171 1169
+f 1177 1175 1179
+f 1177 1179 1180
+f 1180 1179 1181
+f 1181 1182 1183
+f 1184 1180 1185
+f 1177 1180 1184
+f 1186 1177 1184
+f 1176 1177 1186
+f 1187 1176 1186
+f 1178 1176 1187
+f 1188 1178 1187
+f 1189 1190 1191
+f 1190 1192 1193
+f 1192 1190 1189
+f 1194 1168 1195
+f 1196 1194 1195
+f 1192 1194 1196
+f 1193 1192 1196
+f 1193 1196 1197
+f 1198 1199 1200
+f 1198 1201 1202
+f 1198 1202 1199
+f 1199 1202 1203
+f 1198 1204 1205
+f 1198 1205 1206
+f 1206 1201 1198
+f 1201 1207 1202
+f 1206 1205 1208
+f 1199 1209 1200
+f 1198 1210 1204
+f 1211 1212 1213
+f 1213 1212 1214
+f 1212 1215 1214
+f 1214 1215 1216
+f 1217 1218 1219
+f 1220 1218 1217
+f 1220 1221 1218
+f 1222 1221 1220
+f 1219 1215 1223
+f 1219 1223 1217
+f 1217 1223 1224
+f 1225 1217 1224
+f 1220 1217 1225
+f 1226 1220 1225
+f 1222 1220 1226
+f 1226 1227 1222
+f 1222 1227 1221
+f 1227 1228 1221
+f 1229 1221 1228
+f 1230 1229 1228
+f 1231 1229 1230
+f 1231 1232 1229
+f 1233 1232 1231
+f 1234 1228 1227
+f 1234 1227 1226
+f 1221 1235 1218
+f 1229 1235 1221
+f 1232 1235 1229
+f 1236 1235 1232
+f 1211 1237 1238
+f 1211 1238 1212
+f 1212 1238 1239
+f 1239 1215 1212
+f 1239 1240 1215
+f 1223 1215 1240
+f 1224 1223 1241
+f 1242 1243 1244
+f 1244 1243 1240
+f 1244 1240 1239
+f 1244 1239 1242
+f 1239 1245 1242
+f 1238 1245 1239
+f 1246 1247 1248
+f 1248 1247 1249
+f 126 137 125
+f 125 137 1250
+f 1250 124 125
+f 1251 124 1250
+f 1250 137 1252
+f 1250 1252 1253
+f 1250 1253 1254
+f 1254 1251 1250
+f 1255 706 691
+f 1255 691 1256
+f 1256 691 688
+f 687 682 677
+f 1257 324 1258
+f 324 323 1258
+f 1258 323 1259
+f 1259 323 329
+f 1259 329 1260
+f 1260 329 330
+f 1260 330 337
+f 337 330 331
+f 337 331 340
+f 340 331 335
+f 366 368 1261
+f 366 1261 1257
+f 1257 367 366
+f 1258 367 1257
+f 1258 362 367
+f 1259 362 1258
+f 1259 356 362
+f 1260 356 1259
+f 1260 339 356
+f 1260 337 339
+f 1262 318 324
+f 1263 1262 324
+f 324 1257 1263
+f 1263 1257 1261
+f 289 318 1262
+f 291 289 1262
+f 278 291 1262
+f 1262 1263 278
+f 278 1263 276
+f 1261 276 1263
+f 1261 280 276
+f 1261 368 280
+f 280 368 281
+f 281 368 373
+f 1264 701 702
+f 1265 704 705
+f 1266 648 1267
+f 1267 648 645
+f 1268 1269 1270
+f 1271 1270 1269
+f 1270 1271 1272
+f 1273 1272 1271
+f 1274 1275 1276
+f 1276 1277 1274
+f 1278 1277 1276
+f 1279 1280 1281
+f 1279 1281 1282
+f 1283 1280 1279
+f 1284 1283 1279
+f 1285 1283 1284
+f 1286 1282 1287
+f 1287 1282 1288
+f 1282 1281 1288
+f 1214 1216 1
+f 45 53 9
+f 9 13 45
+f 26 15 5
+f 12 26 5
+f 18 26 12
+f 18 12 40
+f 42 18 40
+f 23 19 16
+f 16 19 42
+f 19 18 42
+f 20 21 24
+f 24 21 25
+f 52 36 29
+f 29 53 52
+f 28 53 29
+f 9 53 28
+f 14 42 41
+f 16 42 14
+f 41 13 14
+f 43 13 41
+f 13 43 45
+f 52 51 36
+f 36 51 50
+f 1289 1290 92
+f 84 92 60
+f 60 92 55
+f 55 92 56
+f 92 58 56
+f 1291 58 92
+f 92 1290 1291
+f 1290 57 1291
+f 1291 57 58
+f 61 55 59
+f 73 95 80
+f 74 95 73
+f 74 81 95
+f 85 1289 92
+f 90 1289 85
+f 90 93 1289
+f 1292 93 91
+f 91 88 1292
+f 1292 88 94
+f 61 93 1292
+f 95 67 80
+f 80 67 68
+f 96 80 68
+f 79 80 96
+f 79 96 78
+f 78 96 97
+f 1292 60 61
+f 82 84 60
+f 82 60 1292
+f 1292 94 82
+f 82 94 81
+f 95 81 94
+f 100 115 101
+f 102 101 1293
+f 1293 109 102
+f 116 109 1293
+f 112 109 116
+f 103 112 116
+f 116 104 103
+f 1294 107 106
+f 117 112 118
+f 118 112 103
+f 103 1295 118
+f 105 1295 103
+f 105 108 1295
+f 107 1296 108
+f 1297 1296 107
+f 1297 107 1294
+f 1294 1296 1297
+f 113 115 1298
+f 1298 115 100
+f 100 113 1298
+f 114 113 100
+f 102 114 100
+f 110 114 102
+f 111 112 117
+f 1295 106 104
+f 108 106 1295
+f 108 1294 106
+f 1296 1294 108
+f 115 114 101
+f 114 110 101
+f 101 110 1293
+f 111 1293 110
+f 116 1293 111
+f 111 117 116
+f 116 118 104
+f 104 118 1295
+f 388 1299 1300
+f 1299 387 1300
+f 411 121 120
+f 391 394 392
+f 394 402 392
+f 1301 402 394
+f 403 402 1301
+f 1302 1303 401
+f 1302 401 408
+f 408 401 407
+f 407 401 400
+f 164 123 122
+f 122 124 165
+f 164 128 123
+f 163 128 164
+f 163 131 128
+f 160 167 137
+f 136 160 137
+f 158 160 136
+f 135 158 136
+f 156 158 135
+f 134 156 135
+f 139 156 134
+f 147 139 138
+f 147 138 148
+f 148 138 143
+f 148 143 144
+f 142 141 152
+f 152 143 142
+f 145 143 152
+f 152 141 1304
+f 146 145 152
+f 152 1305 146
+f 152 1304 1305
+f 150 1305 1304
+f 141 150 1304
+f 151 150 141
+f 130 151 141
+f 129 151 130
+f 154 144 146
+f 1305 154 146
+f 153 154 1305
+f 153 1305 150
+f 147 149 139
+f 139 149 1306
+f 152 144 154
+f 144 152 148
+f 129 149 151
+f 129 131 149
+f 149 131 1306
+f 1306 131 157
+f 1306 157 139
+f 139 157 156
+f 122 162 161
+f 157 131 163
+f 164 122 159
+f 159 122 161
+f 165 162 122
+f 1307 162 166
+f 1307 167 162
+f 1308 1309 1310
+f 170 171 1309
+f 1309 1308 170
+f 949 170 1308
+f 949 948 168
+f 170 949 168
+f 169 176 171
+f 173 212 176
+f 173 176 169
+f 948 175 168
+f 1311 175 948
+f 954 175 1311
+f 954 1310 1309
+f 1309 175 954
+f 1309 171 175
+f 175 171 174
+f 171 176 174
+f 179 212 173
+f 212 179 1312
+f 212 1312 1313
+f 176 212 177
+f 177 212 180
+f 184 1314 200
+f 184 200 182
+f 182 200 186
+f 186 200 1315
+f 184 183 197
+f 185 186 955
+f 955 186 956
+f 186 1315 956
+f 956 1315 1316
+f 185 955 188
+f 188 955 963
+f 1315 963 1316
+f 188 963 1315
+f 200 188 1315
+f 187 188 200
+f 190 187 200
+f 183 191 197
+f 189 1317 191
+f 1318 1317 204
+f 204 198 205
+f 198 1314 205
+f 205 1314 184
+f 200 1314 198
+f 203 947 192
+f 192 947 193
+f 200 201 202
+f 201 950 202
+f 202 950 953
+f 193 947 201
+f 201 947 950
+f 953 203 202
+f 202 192 200
+f 200 192 194
+f 200 194 190
+f 190 194 189
+f 189 194 196
+f 189 196 1317
+f 215 213 207
+f 206 215 207
+f 206 208 962
+f 208 961 962
+f 216 961 208
+f 1319 961 216
+f 216 1320 1319
+f 962 1321 206
+f 217 206 1321
+f 217 215 206
+f 1321 1322 217
+f 217 1320 216
+f 217 1322 1320
+f 207 213 219
+f 213 212 219
+f 219 212 1313
+f 219 1313 210
+f 210 1313 181
+f 211 210 181
+f 222 1323 1324
+f 221 1323 222
+f 1324 225 224
+f 1323 225 1324
+f 239 234 237
+f 240 234 239
+f 227 234 240
+f 228 227 240
+f 1325 226 228
+f 230 226 1325
+f 230 1325 1281
+f 1281 229 230
+f 1280 229 1281
+f 1280 1325 229
+f 1326 1325 1280
+f 1281 1325 1326
+f 1325 228 229
+f 229 228 231
+f 240 232 228
+f 228 232 231
+f 1327 985 241
+f 241 985 242
+f 244 238 235
+f 235 238 237
+f 237 234 235
+f 985 245 242
+f 246 241 244
+f 244 241 238
+f 1327 241 245
+f 245 241 246
+f 253 254 247
+f 247 254 248
+f 257 258 1076
+f 1076 261 1077
+f 1076 258 261
+f 1328 260 259
+f 349 263 262
+f 264 265 1328
+f 1328 265 266
+f 266 260 1328
+f 1077 261 268
+f 1077 268 1078
+f 270 1078 271
+f 271 1078 273
+f 1078 268 273
+f 277 263 349
+f 349 292 277
+f 345 290 291
+f 291 292 345
+f 1174 293 295
+f 306 296 284
+f 288 306 284
+f 344 306 288
+f 290 344 288
+f 343 344 290
+f 343 290 345
+f 305 298 296
+f 305 296 306
+f 297 298 1182
+f 298 1329 1182
+f 1329 298 305
+f 1182 1329 1330
+f 303 1329 305
+f 304 1329 303
+f 1329 304 1330
+f 1330 304 1191
+f 304 1189 1191
+f 301 1189 304
+f 301 307 1189
+f 309 1172 308
+f 313 1172 309
+f 313 1174 1172
+f 310 1174 313
+f 310 293 1174
+f 345 292 346
+f 346 292 349
+f 349 262 347
+f 354 262 264
+f 351 262 354
+f 347 262 351
+f 354 264 361
+f 361 259 381
+f 259 256 381
+f 381 256 382
+f 255 382 256
+f 383 382 255
+f 384 1054 380
+f 380 1054 378
+f 1054 1056 378
+f 378 1056 269
+f 1056 270 269
+f 361 264 1328
+f 1328 259 361
+f 387 386 1300
+f 1300 386 388
+f 1299 390 387
+f 385 390 409
+f 385 409 386
+f 386 409 1331
+f 1332 386 1331
+f 389 386 1332
+f 389 1332 390
+f 389 390 388
+f 388 390 1299
+f 390 1332 410
+f 409 390 410
+f 1301 394 396
+f 1301 396 403
+f 403 396 398
+f 397 401 1303
+f 397 1303 399
+f 399 1303 1302
+f 408 399 1302
+f 406 399 408
+f 406 398 399
+f 404 398 406
+f 404 403 398
+f 410 1332 121
+f 121 1332 119
+f 1332 120 119
+f 1331 120 1332
+f 1331 409 120
+f 120 409 411
+f 411 410 121
+f 413 467 468
+f 466 467 413
+f 466 413 412
+f 444 412 415
+f 418 444 415
+f 417 444 418
+f 425 416 1333
+f 1333 416 421
+f 421 418 442
+f 418 415 442
+f 442 415 440
+f 415 414 440
+f 440 414 437
+f 414 438 437
+f 413 438 414
+f 424 425 1333
+f 458 426 428
+f 428 427 453
+f 427 422 453
+f 431 429 447
+f 447 429 427
+f 447 427 445
+f 445 427 426
+f 1334 445 426
+f 450 445 1334
+f 1335 450 1334
+f 461 450 1335
+f 435 461 1335
+f 459 461 435
+f 459 435 460
+f 460 435 432
+f 1336 460 434
+f 434 460 432
+f 433 435 455
+f 435 1335 455
+f 455 1335 457
+f 1335 1334 457
+f 457 1334 458
+f 1334 426 458
+f 442 443 421
+f 421 443 1337
+f 1338 421 1337
+f 1333 421 1338
+f 1333 1338 424
+f 1338 420 1339
+f 1338 1337 420
+f 420 1337 419
+f 1337 417 419
+f 443 417 1337
+f 443 444 417
+f 441 412 444
+f 439 412 441
+f 439 462 412
+f 447 448 431
+f 448 430 431
+f 1339 430 448
+f 1339 420 430
+f 453 422 446
+f 446 422 448
+f 422 424 448
+f 448 424 1339
+f 424 1338 1339
+f 458 428 449
+f 449 428 452
+f 428 453 452
+f 433 455 454
+f 433 454 436
+f 436 454 1340
+f 1340 454 1336
+f 1336 454 460
+f 469 463 438
+f 469 464 463
+f 465 1341 463
+f 463 1341 467
+f 412 462 466
+f 469 470 464
+f 413 469 438
+f 467 470 468
+f 1341 470 467
+f 472 1342 474
+f 481 487 483
+f 483 487 484
+f 484 487 1343
+f 1343 1344 484
+f 484 1344 486
+f 1345 484 485
+f 482 484 1345
+f 482 1345 487
+f 487 1345 1343
+f 1343 1345 1344
+f 520 480 487
+f 520 478 480
+f 488 478 520
+f 519 477 488
+f 475 477 519
+f 471 477 475
+f 475 489 471
+f 493 491 494
+f 494 491 1342
+f 1342 491 474
+f 474 491 489
+f 474 489 475
+f 490 1342 472
+f 490 494 1342
+f 494 496 493
+f 506 496 494
+f 506 499 496
+f 515 499 506
+f 508 517 511
+f 511 517 516
+f 511 516 501
+f 501 516 502
+f 505 515 498
+f 498 515 500
+f 515 506 500
+f 505 497 515
+f 497 505 514
+f 514 505 504
+f 502 514 504
+f 513 514 502
+f 516 513 502
+f 1344 509 518
+f 485 509 1344
+f 485 507 509
+f 486 507 485
+f 486 1344 507
+f 507 1344 518
+f 507 518 508
+f 508 518 517
+f 519 488 476
+f 476 488 479
+f 488 520 479
+f 520 487 481
+f 1344 1345 485
+f 523 601 536
+f 535 601 523
+f 535 537 601
+f 544 545 594
+f 545 551 594
+f 594 551 595
+f 551 549 595
+f 595 549 597
+f 549 521 597
+f 597 521 546
+f 562 561 574
+f 564 562 568
+f 564 565 562
+f 562 565 569
+f 568 562 574
+f 578 577 585
+f 580 575 573
+f 575 574 573
+f 573 574 566
+f 574 561 566
+f 590 588 1346
+f 588 589 1346
+f 582 589 588
+f 582 585 589
+f 578 585 582
+f 583 577 580
+f 577 575 580
+f 585 577 583
+f 1346 589 586
+f 1346 586 590
+f 593 588 590
+f 569 558 562
+f 569 542 558
+f 558 542 557
+f 542 544 557
+f 557 544 556
+f 544 594 556
+f 597 546 598
+f 598 546 599
+f 546 600 599
+f 536 600 546
+f 539 530 538
+f 538 530 528
+f 538 528 537
+f 537 528 526
+f 537 526 601
+f 601 525 536
+f 536 525 600
+f 605 616 603
+f 619 616 605
+f 606 619 605
+f 611 619 606
+f 611 606 541
+f 541 606 532
+f 541 532 539
+f 539 532 530
+f 616 615 603
+f 618 615 616
+f 618 625 615
+f 638 625 618
+f 638 627 625
+f 637 627 638
+f 637 622 627
+f 620 622 637
+f 623 636 639
+f 635 636 623
+f 620 635 623
+f 634 635 620
+f 637 634 620
+f 643 640 636
+f 636 640 639
+f 652 647 1267
+f 647 1266 1267
+f 649 1266 647
+f 1266 649 653
+f 661 668 666
+f 661 666 658
+f 658 666 667
+f 667 659 658
+f 659 651 656
+f 656 651 657
+f 651 644 657
+f 659 663 651
+f 659 662 663
+f 665 662 659
+f 659 667 665
+f 685 677 674
+f 683 674 679
+f 679 674 672
+f 679 672 680
+f 680 672 670
+f 680 670 681
+f 681 670 668
+f 681 668 661
+f 683 685 674
+f 684 1256 685
+f 690 1256 684
+f 694 1256 690
+f 1255 1256 694
+f 695 1255 694
+f 709 1255 695
+f 1265 709 697
+f 707 1265 697
+f 710 1265 707
+f 1264 710 708
+f 711 1264 708
+f 711 1347 1348
+f 1348 1264 711
+f 715 714 729
+f 715 729 717
+f 717 729 1349
+f 1349 1347 717
+f 717 1347 716
+f 716 1347 711
+f 728 721 714
+f 714 721 729
+f 729 720 1349
+f 733 728 724
+f 724 728 714
+f 725 733 724
+f 736 733 725
+f 730 736 725
+f 735 736 730
+f 730 737 735
+f 739 1350 731
+f 731 1350 730
+f 1350 737 730
+f 743 740 1351
+f 744 743 1351
+f 1351 740 795
+f 749 745 744
+f 747 744 741
+f 741 744 1351
+f 1351 795 741
+f 741 795 742
+f 742 795 792
+f 747 749 744
+f 748 756 749
+f 760 764 750
+f 750 764 751
+f 753 756 752
+f 752 756 754
+f 754 756 748
+f 749 755 745
+f 756 755 749
+f 764 758 751
+f 758 757 751
+f 751 757 753
+f 757 756 753
+f 765 767 1352
+f 1352 767 768
+f 770 762 760
+f 760 762 764
+f 770 763 762
+f 766 768 771
+f 768 763 771
+f 771 763 772
+f 772 763 770
+f 1352 768 766
+f 786 776 787
+f 776 773 787
+f 787 773 788
+f 778 776 786
+f 786 780 778
+f 781 780 786
+f 785 781 777
+f 777 781 786
+f 792 795 796
+f 796 797 792
+f 792 797 789
+f 797 790 789
+f 790 779 784
+f 779 781 784
+f 784 781 785
+f 797 793 790
+f 790 793 794
+f 779 790 794
+f 1353 1354 799
+f 803 799 798
+f 799 1354 800
+f 800 1354 1355
+f 1356 1355 1354
+f 1357 1358 802
+f 802 1359 1357
+f 1360 1359 802
+f 1361 1359 1360
+f 1360 1362 1361
+f 802 801 1360
+f 1356 1361 1355
+f 1359 1361 1356
+f 1354 1359 1356
+f 1357 1359 1354
+f 1353 1357 1354
+f 1358 1357 1353
+f 799 1358 1353
+f 802 1358 799
+f 803 802 799
+f 798 801 803
+f 1360 801 798
+f 800 1360 798
+f 1362 1360 800
+f 1355 1362 800
+f 1361 1362 1355
+f 848 829 826
+f 831 829 848
+f 860 857 861
+f 855 857 860
+f 861 1363 862
+f 1363 1364 862
+f 862 1364 856
+f 856 1364 857
+f 857 1364 1365
+f 857 1365 861
+f 861 1365 1366
+f 1366 1363 861
+f 869 864 1367
+f 865 864 869
+f 867 863 872
+f 867 872 1368
+f 1368 872 868
+f 872 869 868
+f 1367 871 869
+f 1367 1368 871
+f 867 1368 1367
+f 872 865 869
+f 878 1369 880
+f 1369 883 880
+f 883 918 881
+f 881 918 882
+f 918 884 882
+f 888 909 889
+f 912 888 887
+f 912 887 890
+f 891 885 917
+f 917 885 884
+f 917 884 918
+f 889 909 895
+f 909 914 895
+f 899 920 873
+f 873 920 876
+f 920 900 876
+f 900 1369 878
+f 897 896 1370
+f 1370 896 901
+f 903 1370 901
+f 906 1370 903
+f 907 904 914
+f 914 904 905
+f 895 914 905
+f 909 888 910
+f 910 888 911
+f 888 912 911
+f 907 914 908
+f 907 908 906
+f 908 1370 906
+f 1370 908 897
+f 897 908 910
+f 910 898 897
+f 911 898 910
+f 911 899 898
+f 913 899 911
+f 913 915 899
+f 915 912 890
+f 915 890 919
+f 919 890 891
+f 891 916 919
+f 917 916 891
+f 883 916 918
+f 883 1369 916
+f 1369 900 916
+f 916 900 919
+f 920 919 900
+f 899 915 920
+f 1371 929 927
+f 928 1371 927
+f 1372 1371 928
+f 923 1372 928
+f 1373 1372 923
+f 922 1373 923
+f 925 1373 922
+f 925 924 929
+f 1373 925 1372
+f 1372 925 929
+f 1371 1372 929
+f 1374 933 935
+f 936 1374 935
+f 938 1374 936
+f 1375 938 937
+f 931 1375 937
+f 1376 1375 931
+f 930 1376 931
+f 934 1376 930
+f 1375 1374 938
+f 1375 1376 934
+f 934 1374 1375
+f 934 933 1374
+f 1377 1378 1379
+f 1379 1378 1380
+f 1381 940 939
+f 1380 1378 1381
+f 1381 939 1380
+f 1379 1380 939
+f 939 941 1379
+f 1377 1379 941
+f 941 940 1377
+f 1378 1377 940
+f 940 1381 1378
+f 1270 1272 1268
+f 1272 1382 1268
+f 947 203 948
+f 948 203 1311
+f 1311 203 954
+f 954 203 953
+f 949 1308 943
+f 943 1308 952
+f 952 1308 1310
+f 944 943 952
+f 945 944 951
+f 951 950 945
+f 950 951 953
+f 944 952 951
+f 1310 954 952
+f 956 1316 1383
+f 1383 957 956
+f 1383 1384 957
+f 960 1384 1385
+f 959 1384 960
+f 957 1384 959
+f 960 1321 962
+f 1385 1321 960
+f 1385 1322 1321
+f 963 961 1319
+f 1319 1320 963
+f 963 1320 1316
+f 1386 1275 1277
+f 1277 1275 1274
+f 249 251 247
+f 251 253 247
+f 1387 970 964
+f 964 970 965
+f 1387 969 970
+f 1388 972 971
+f 975 1389 971
+f 971 1389 1390
+f 1390 1391 971
+f 971 1391 1388
+f 980 977 1392
+f 1392 977 1393
+f 1393 977 1394
+f 1394 977 1395
+f 1395 977 976
+f 1396 1397 981
+f 981 1397 982
+f 1397 1398 982
+f 982 1398 989
+f 982 989 984
+f 984 989 986
+f 984 986 245
+f 245 985 984
+f 983 985 981
+f 981 985 1327
+f 1327 1396 981
+f 1399 1396 1327
+f 1399 1327 987
+f 245 987 1327
+f 988 987 245
+f 245 986 988
+f 989 1399 987
+f 1398 1399 989
+f 991 993 1400
+f 1401 990 992
+f 1401 993 990
+f 1400 993 1401
+f 1002 998 1010
+f 1009 1002 1010
+f 994 1002 1009
+f 1009 995 994
+f 1005 1006 995
+f 995 1009 1005
+f 1019 1045 1018
+f 1402 1016 1020
+f 1021 1016 1402
+f 1042 1013 1021
+f 1042 1000 1013
+f 1403 1402 1018
+f 1018 1402 1020
+f 1018 1045 1403
+f 1404 1405 1406
+f 1407 1405 1404
+f 1408 1407 1404
+f 1408 1404 1400
+f 1400 1404 991
+f 1404 1406 991
+f 991 1406 1409
+f 991 1409 992
+f 992 1409 1410
+f 992 1410 1023
+f 1023 1410 1411
+f 1412 1407 1408
+f 1408 1061 1412
+f 1408 1060 1061
+f 1400 1060 1408
+f 1400 1050 1060
+f 1401 1050 1400
+f 1401 1051 1050
+f 1022 1051 1401
+f 1022 1071 1051
+f 1024 1071 1022
+f 1412 1061 1413
+f 1401 992 1022
+f 1022 992 1023
+f 1023 1411 1025
+f 1025 1411 1414
+f 1025 1414 1027
+f 1027 1414 1415
+f 1027 1415 1029
+f 1029 1415 1034
+f 1031 1034 1036
+f 1031 1036 1033
+f 1033 1036 1039
+f 1032 1033 1412
+f 1412 1033 1407
+f 1033 1039 1407
+f 1407 1039 1405
+f 1024 1069 1071
+f 1026 1069 1024
+f 1026 1035 1069
+f 1028 1065 1035
+f 1030 1065 1028
+f 1030 1066 1065
+f 1032 1066 1030
+f 1032 1413 1066
+f 1412 1413 1032
+f 1414 1089 1415
+f 1415 1089 1088
+f 1415 1088 1034
+f 1034 1088 1037
+f 1034 1037 1036
+f 1039 1038 1094
+f 1039 1094 1405
+f 1405 1094 1093
+f 1405 1093 1406
+f 1406 1093 1416
+f 1406 1416 1409
+f 1409 1416 1092
+f 1409 1092 1410
+f 1410 1092 1417
+f 1410 1417 1411
+f 1411 1417 1090
+f 1411 1090 1414
+f 1414 1090 1089
+f 1011 1000 1043
+f 998 1000 1011
+f 1010 998 1011
+f 1042 1043 1000
+f 1045 1044 1403
+f 1403 1044 1402
+f 1044 1021 1402
+f 1040 1021 1044
+f 1040 1042 1021
+f 1047 270 1056
+f 1046 270 1047
+f 1049 997 1048
+f 1006 997 1049
+f 1049 1047 1006
+f 1006 1047 995
+f 1047 1052 995
+f 1052 1051 995
+f 1059 384 383
+f 1055 384 1059
+f 1055 1054 384
+f 1047 1056 1053
+f 1053 1052 1047
+f 1058 1413 1061
+f 1062 1413 1058
+f 1059 255 1063
+f 383 255 1059
+f 1051 1071 995
+f 995 1071 996
+f 1062 1066 1413
+f 1064 1066 1062
+f 1067 1035 1065
+f 1070 1035 1067
+f 1070 1069 1035
+f 996 1071 1068
+f 996 1068 1046
+f 996 1046 997
+f 997 1046 1048
+f 1064 1062 1075
+f 1075 1062 1063
+f 255 257 1063
+f 1063 257 1075
+f 257 1076 1075
+f 1078 270 1072
+f 1072 270 1046
+f 1417 1084 1090
+f 1080 1084 1417
+f 1092 1080 1417
+f 1416 1081 1092
+f 1079 1081 1416
+f 1093 1079 1416
+f 1038 1086 1094
+f 1091 1086 1038
+f 1037 1091 1038
+f 1087 1091 1037
+f 1088 1087 1037
+f 1096 1117 1097
+f 1097 1117 1098
+f 1095 1098 1102
+f 1117 1102 1098
+f 1197 1118 1119
+f 1096 1100 1418
+f 1418 1100 1197
+f 1100 1118 1197
+f 1118 1100 1099
+f 1101 1096 1095
+f 1100 1096 1101
+f 1099 1101 1419
+f 1419 1101 1420
+f 1101 1095 1420
+f 1420 1095 1421
+f 1095 1102 1421
+f 1421 1102 1104
+f 1111 1113 1186
+f 1186 1113 1187
+f 1113 1115 1187
+f 1187 1115 1188
+f 1115 1116 1188
+f 1188 1116 1422
+f 1116 1117 1422
+f 1422 1117 1423
+f 1117 1096 1423
+f 1423 1096 1418
+f 1122 1099 1419
+f 1108 1099 1122
+f 1108 1118 1099
+f 1119 1107 1185
+f 1107 1109 1185
+f 1185 1109 1184
+f 1109 1111 1184
+f 1184 1111 1186
+f 1105 1114 1124
+f 1114 1112 1124
+f 1124 1112 1120
+f 1120 1110 1424
+f 1110 1106 1424
+f 1424 1106 1121
+f 1419 1420 1425
+f 1425 1420 1210
+f 1420 1421 1210
+f 1210 1421 1426
+f 1421 1104 1426
+f 1426 1104 1427
+f 1104 1105 1427
+f 1427 1105 1123
+f 1105 1124 1123
+f 1124 1120 1125
+f 1125 1120 1207
+f 1120 1424 1207
+f 1207 1424 1428
+f 1424 1121 1428
+f 1428 1121 1429
+f 1121 1122 1429
+f 1429 1122 1209
+f 1122 1419 1209
+f 1209 1419 1425
+f 1127 1157 1156
+f 1156 1128 1127
+f 1128 1155 1126
+f 1135 1137 1151
+f 1145 1152 1153
+f 1151 1152 1145
+f 1145 1138 1151
+f 1151 1138 1135
+f 1136 1140 1137
+f 1137 1140 1143
+f 1149 1137 1143
+f 1150 1146 1169
+f 1146 1145 1169
+f 1169 1145 1167
+f 1153 1167 1145
+f 1151 1137 1149
+f 1169 1154 1150
+f 1157 1126 1155
+f 1162 1159 1158
+f 1164 1141 1132
+f 1132 1141 1136
+f 1136 1141 1140
+f 1161 1165 1163
+f 1161 1162 1165
+f 1165 1162 1158
+f 1158 1164 1165
+f 1165 1164 1130
+f 1164 1132 1130
+f 1172 1168 308
+f 1168 1167 1153
+f 1166 1168 1170
+f 1170 1168 1171
+f 1171 1168 1172
+f 1171 1178 1154
+f 1169 1171 1154
+f 1175 1174 295
+f 1175 295 1179
+f 1179 295 297
+f 1179 297 1181
+f 1181 297 1182
+f 1183 1182 1330
+f 1430 1181 1183
+f 1180 1181 1430
+f 1180 1430 1185
+f 1185 1430 1119
+f 1154 1178 1188
+f 1154 1188 1153
+f 1153 1188 1422
+f 1183 1330 1190
+f 1190 1330 1191
+f 1430 1183 1193
+f 1193 1183 1190
+f 307 1192 1189
+f 1194 1192 307
+f 308 1194 307
+f 1168 1194 308
+f 1195 1168 1153
+f 1153 1422 1195
+f 1195 1422 1423
+f 1418 1195 1423
+f 1196 1195 1418
+f 1197 1196 1418
+f 1119 1193 1197
+f 1430 1193 1119
+f 1206 1125 1201
+f 1201 1125 1207
+f 1202 1207 1428
+f 1202 1428 1203
+f 1203 1428 1429
+f 1203 1429 1199
+f 1199 1429 1209
+f 1200 1209 1425
+f 1200 1425 1198
+f 1198 1425 1210
+f 1204 1210 1426
+f 1204 1426 1205
+f 1205 1426 1427
+f 1205 1427 1208
+f 1208 1427 1123
+f 1208 1123 1206
+f 1206 1123 1125
+f 3 2 1218
+f 2 1 1218
+f 1431 1213 1
+f 1213 1214 1
+f 1432 1211 1433
+f 1433 1211 1213
+f 1216 1215 1
+f 1215 1219 1
+f 1 1219 1218
+f 1230 1228 1234
+f 1433 1213 1434
+f 1434 1213 1431
+f 1236 1434 1431
+f 1431 1 1236
+f 1236 1 3
+f 3 1235 1236
+f 1218 1235 3
+f 1232 1435 1236
+f 1233 1435 1232
+f 1435 1434 1236
+f 1240 1243 1436
+f 1432 1237 1211
+f 1240 1436 1223
+f 1223 1436 1241
+f 1437 1438 1245
+f 1245 1438 1242
+f 1438 1243 1242
+f 1238 1437 1245
+f 1237 1437 1238
+f 1436 1243 1241
+f 1437 1237 1432
+f 1438 1437 1432
+f 1243 1438 1432
+f 1432 1434 1243
+f 1241 1243 1434
+f 1241 1434 1224
+f 1434 1226 1224
+f 1224 1226 1225
+f 1433 1434 1432
+f 1434 1233 1226
+f 1435 1233 1434
+f 1233 1231 1230
+f 1230 1234 1233
+f 1226 1233 1234
+f 1366 870 1363
+f 1363 870 871
+f 1363 871 1364
+f 1364 871 1368
+f 1368 868 1364
+f 1364 868 1365
+f 868 1366 1365
+f 870 1366 868
+f 165 124 1251
+f 1254 165 1251
+f 166 165 1254
+f 1253 166 1254
+f 1307 166 1253
+f 1307 1253 167
+f 167 1253 1252
+f 137 167 1252
+f 1265 705 709
+f 709 705 706
+f 709 706 1255
+f 1256 688 685
+f 685 688 687
+f 687 677 685
+f 720 699 1349
+f 1349 699 1347
+f 1347 699 1348
+f 1348 699 701
+f 1348 701 1264
+f 1264 702 710
+f 710 702 704
+f 710 704 1265
+f 648 653 655
+f 1266 653 648
+f 1267 645 652
+f 652 645 644
+f 652 644 651
+f 1273 1271 1269
+f 1439 1273 1269
+f 1269 1268 1439
+f 1272 1273 1382
+f 1439 1382 1273
+f 1382 1439 1268
+f 1385 1320 1322
+f 1316 1320 1385
+f 1316 1385 1383
+f 1383 1385 1384
+f 1276 1275 1440
+f 1278 1386 1277
+f 1441 1386 1278
+f 1440 1386 1441
+f 1275 1386 1440
+f 1395 974 1394
+f 975 974 1395
+f 976 975 1395
+f 1389 975 976
+f 978 1389 976
+f 1390 1389 978
+f 979 1390 978
+f 1391 1390 979
+f 980 1391 979
+f 1388 1391 980
+f 1392 1388 980
+f 972 1388 1392
+f 1393 972 1392
+f 973 972 1393
+f 1394 973 1393
+f 974 973 1394
+f 1286 1279 1282
+f 1284 1279 1286
+f 1442 1284 1286
+f 1443 1284 1442
+f 1326 1280 1285
+f 1285 1280 1283
+f 1443 1285 1284
+f 1444 1285 1443
+f 1442 1286 1445
+f 1445 1286 1287
+f 1288 1281 1287
+f 1287 1281 1326
+f 1445 1287 1326
+f 1445 1326 1444
+f 1444 1326 1285
+# 2668 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/gears.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/gears.obj
new file mode 100644
index 0000000000..c51f4a6300
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/gears.obj
@@ -0,0 +1,2398 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object gears.obj
+#
+# Vertices: 794
+# Faces: 1588
+#
+####
+v 0.125861 -0.222767 0.349753
+v 0.125861 -0.249981 0.330771
+v 0.115460 0.041437 -0.010912
+v 0.115460 0.000616 -0.037488
+v 0.104512 0.010821 -0.048877
+v 0.104512 -0.003920 0.068814
+v 0.104512 0.044839 -0.022302
+v 0.104512 0.049374 0.000477
+v -0.032888 0.030098 0.030849
+v -0.046573 0.235337 -0.367781
+v -0.046573 0.205855 -0.382967
+v -0.032888 -0.025464 0.000477
+v -0.025772 0.210391 -0.390560
+v -0.025772 0.197918 -0.382967
+v -0.025772 0.171838 -0.238701
+v -0.025772 0.238739 -0.360188
+v -0.023582 -0.001652 0.201691
+v -0.023582 -0.026599 0.197894
+v -0.023582 -0.015259 0.213080
+v -0.023582 -0.027732 0.163726
+v -0.023582 -0.051545 0.194098
+v -0.023582 -0.041340 0.209283
+v -0.023582 -0.115044 0.178912
+v -0.023582 -0.096902 0.175115
+v -0.023582 -0.118446 0.163726
+v -0.023582 -0.096902 0.137150
+v -0.023582 -0.052679 0.159929
+v -0.023582 -0.075357 0.186505
+v -0.023582 -0.067420 0.201691
+v -0.023582 -0.092366 0.194098
+v -0.023582 -0.136589 0.163726
+v -0.023582 -0.137723 0.144743
+v -0.023582 -0.132053 0.099186
+v -0.023582 -0.153598 0.125761
+v -0.023582 -0.168338 0.106779
+v -0.023582 -0.171740 0.125761
+v -0.023582 -0.155865 0.144743
+v -0.023582 -0.179678 0.084000
+v -0.023582 -0.185347 0.102982
+v -0.023582 -0.154731 0.057424
+v -0.023582 -0.188749 0.061221
+v -0.023582 -0.158133 0.030849
+v -0.023582 -0.194419 0.038442
+v -0.023582 -0.196686 0.011867
+v -0.023582 -0.208026 0.027052
+v -0.023582 -0.196686 0.076407
+v -0.023582 -0.204624 0.053628
+v -0.023582 -0.195553 -0.010912
+v -0.023582 -0.209160 0.000477
+v -0.023582 -0.158133 -0.018505
+v -0.023582 -0.001652 0.030849
+v -0.023582 -0.192151 -0.037488
+v -0.023582 -0.206892 -0.026098
+v -0.023582 -0.154731 -0.045081
+v -0.023582 -0.179678 -0.102028
+v -0.023582 -0.174008 -0.083045
+v -0.023582 -0.161535 -0.105824
+v -0.023582 -0.132053 -0.090638
+v -0.023582 -0.184213 -0.060267
+v -0.023582 -0.201222 -0.052674
+v -0.023582 -0.191017 -0.079249
+v -0.023582 -0.163803 -0.124807
+v -0.023582 -0.145660 -0.124807
+v -0.023582 -0.096901 -0.124807
+v -0.023582 -0.128651 -0.139993
+v -0.023582 -0.108241 -0.155178
+v -0.023582 -0.126383 -0.158975
+v -0.023582 -0.145660 -0.143789
+v -0.023582 -0.086696 -0.170364
+v -0.023582 -0.103705 -0.174161
+v -0.023582 -0.052679 -0.147585
+v -0.023582 -0.062884 -0.177957
+v -0.023582 -0.039071 -0.185550
+v -0.023582 -0.054946 -0.193143
+v -0.023582 -0.079893 -0.185550
+v -0.023582 -0.027732 -0.151382
+v -0.023582 -0.014125 -0.189347
+v -0.023582 -0.028866 -0.200736
+v -0.023582 0.010821 -0.189347
+v -0.023582 0.023294 -0.151382
+v -0.023582 0.035767 -0.185550
+v -0.023582 0.048240 -0.147585
+v -0.023582 0.059580 -0.177957
+v -0.023582 0.082258 -0.170364
+v -0.023582 0.075454 -0.185550
+v -0.023582 0.050508 -0.193143
+v -0.023582 -0.001652 -0.200736
+v -0.023582 0.024428 -0.200736
+v -0.023582 0.103802 -0.155178
+v -0.023582 0.099267 -0.174161
+v -0.023582 0.092463 -0.124807
+v -0.023582 0.121945 -0.158975
+v -0.023582 0.124213 -0.139993
+v -0.023582 0.142356 -0.124807
+v -0.023582 0.127615 -0.090638
+v -0.023582 0.157097 -0.105824
+v -0.023582 0.170704 -0.083045
+v -0.023582 0.175239 -0.102028
+v -0.023582 0.142356 -0.143789
+v -0.023582 0.160498 -0.124807
+v -0.023582 0.180909 -0.060267
+v -0.023582 0.187713 -0.079249
+v -0.023582 0.150293 -0.045081
+v -0.023582 0.196784 -0.052674
+v -0.023582 0.187713 -0.037488
+v -0.023582 0.154829 -0.018505
+v -0.023582 0.191114 -0.010912
+v -0.023582 0.202453 -0.026098
+v -0.023582 0.192248 0.011867
+v -0.023582 0.204721 0.000477
+v -0.023582 0.154829 0.030849
+v -0.023582 0.189980 0.038442
+v -0.023582 0.184311 0.061221
+v -0.023582 0.200186 0.053628
+v -0.023582 0.204721 0.027052
+v -0.023582 0.192248 0.076407
+v -0.023582 0.176373 0.084000
+v -0.023582 0.163900 0.106779
+v -0.023582 0.182043 0.102982
+v -0.023582 0.150293 0.057424
+v -0.023582 0.127615 0.099186
+v -0.023582 0.150293 0.125761
+v -0.023582 0.168436 0.125761
+v -0.023582 0.133284 0.144743
+v -0.023582 0.151427 0.144743
+v -0.023582 0.092463 0.137150
+v -0.023582 0.114008 0.163726
+v -0.023582 0.093597 0.175115
+v -0.023582 0.110606 0.178912
+v -0.023582 0.132150 0.163726
+v -0.023582 0.070919 0.186505
+v -0.023582 0.087928 0.194098
+v -0.023582 0.048240 0.159929
+v -0.023582 0.062981 0.201691
+v -0.023582 0.047106 0.194098
+v -0.023582 0.023294 0.163726
+v -0.023582 0.023294 0.197894
+v -0.023582 0.010821 0.213080
+v -0.023582 0.038035 0.209283
+v -0.014823 -0.179678 0.084000
+v -0.014823 -0.185347 0.102982
+v -0.014823 -0.168338 0.106779
+v -0.014823 -0.196686 0.076407
+v -0.014823 -0.188749 0.061221
+v -0.014823 -0.194419 0.038442
+v -0.014823 -0.204624 0.053628
+v -0.014823 -0.208026 0.027052
+v -0.014823 -0.196686 0.011867
+v -0.014823 -0.158133 0.030849
+v -0.014823 -0.154731 0.057424
+v -0.014823 -0.132053 0.099186
+v -0.014823 -0.153598 0.125761
+v -0.014823 -0.171740 0.125761
+v -0.014823 -0.155865 0.144743
+v -0.014823 -0.137723 0.144743
+v -0.014823 -0.096902 0.137150
+v -0.014823 -0.001652 0.030849
+v -0.014823 -0.158133 -0.018505
+v -0.014823 -0.201222 -0.052674
+v -0.014823 -0.192151 -0.037488
+v -0.014823 -0.184213 -0.060267
+v -0.014823 -0.154731 -0.045081
+v -0.014823 -0.195553 -0.010912
+v -0.014823 -0.209160 0.000477
+v -0.014823 -0.206892 -0.026098
+v -0.014823 -0.174008 -0.083045
+v -0.014823 -0.191017 -0.079249
+v -0.014823 -0.132053 -0.090638
+v -0.014823 -0.128651 -0.139993
+v -0.014823 -0.145660 -0.143789
+v -0.014823 -0.145660 -0.124807
+v -0.014823 -0.096901 -0.124807
+v -0.014823 -0.161535 -0.105824
+v -0.014823 -0.179678 -0.102028
+v -0.014823 -0.163803 -0.124807
+v -0.014823 -0.054946 -0.193143
+v -0.014823 -0.062884 -0.177957
+v -0.014823 -0.039071 -0.185550
+v -0.014823 -0.052679 -0.147585
+v -0.014823 -0.086696 -0.170364
+v -0.014823 -0.108241 -0.155178
+v -0.014823 -0.126383 -0.158975
+v -0.014823 -0.103705 -0.174161
+v -0.014823 -0.079893 -0.185550
+v -0.014823 -0.014125 -0.189347
+v -0.014823 -0.028866 -0.200736
+v -0.014823 -0.027732 -0.151382
+v -0.014823 -0.001652 -0.200736
+v -0.014823 0.010821 -0.189347
+v -0.014823 0.023294 -0.151382
+v -0.014823 0.035767 -0.185550
+v -0.014823 0.024428 -0.200736
+v -0.014823 0.048240 -0.147585
+v -0.014823 0.103802 -0.155178
+v -0.014823 0.099267 -0.174161
+v -0.014823 0.082258 -0.170364
+v -0.014823 0.092463 -0.124807
+v -0.014823 0.059580 -0.177957
+v -0.014823 0.050508 -0.193143
+v -0.014823 0.075454 -0.185550
+v -0.014823 0.160498 -0.124807
+v -0.014823 0.142356 -0.124807
+v -0.014823 0.157097 -0.105824
+v -0.014823 0.127615 -0.090638
+v -0.014823 0.124213 -0.139993
+v -0.014823 0.121945 -0.158975
+v -0.014823 0.142356 -0.143789
+v -0.014823 0.175239 -0.102028
+v -0.014823 0.170704 -0.083045
+v -0.014823 0.150293 -0.045081
+v -0.014823 0.191114 -0.010912
+v -0.014823 0.202453 -0.026098
+v -0.014823 0.187713 -0.037488
+v -0.014823 0.154829 -0.018505
+v -0.014823 0.180909 -0.060267
+v -0.014823 0.187713 -0.079249
+v -0.014823 0.196784 -0.052674
+v -0.014823 0.192248 0.011867
+v -0.014823 0.204721 0.000477
+v -0.014823 0.154829 0.030849
+v -0.014823 0.163900 0.106779
+v -0.014823 0.182043 0.102982
+v -0.014823 0.176373 0.084000
+v -0.014823 0.127615 0.099186
+v -0.014823 0.150293 0.057424
+v -0.014823 0.184311 0.061221
+v -0.014823 0.189980 0.038442
+v -0.014823 0.204721 0.027052
+v -0.014823 0.192248 0.076407
+v -0.014823 0.200186 0.053628
+v -0.014823 0.132150 0.163726
+v -0.014823 0.133284 0.144743
+v -0.014823 0.114008 0.163726
+v -0.014823 0.092463 0.137150
+v -0.014823 0.150293 0.125761
+v -0.014823 0.168436 0.125761
+v -0.014823 0.151427 0.144743
+v -0.014823 0.110606 0.178912
+v -0.014823 0.093597 0.175115
+v -0.014823 0.048240 0.159929
+v -0.014823 0.010821 0.213080
+v -0.014823 0.023294 0.197894
+v -0.014823 -0.001652 0.201691
+v -0.014823 0.023294 0.163726
+v -0.014823 0.047106 0.194098
+v -0.014823 0.070919 0.186505
+v -0.014823 0.087928 0.194098
+v -0.014823 0.038035 0.209283
+v -0.014823 0.062981 0.201691
+v -0.014823 -0.026599 0.197894
+v -0.014823 -0.015259 0.213080
+v -0.014823 -0.027732 0.163726
+v -0.014823 -0.051545 0.194098
+v -0.014823 -0.041340 0.209283
+v -0.014823 -0.052679 0.159929
+v -0.014823 -0.067420 0.201691
+v -0.014823 -0.075357 0.186505
+v -0.014823 -0.096902 0.175115
+v -0.014823 -0.118446 0.163726
+v -0.014823 -0.136589 0.163726
+v -0.014823 -0.092366 0.194098
+v -0.014823 -0.115044 0.178912
+v -0.003875 0.075454 -0.102028
+v -0.003875 0.055044 -0.113417
+v -0.003875 0.064115 -0.083045
+v -0.003875 0.033499 -0.102028
+v -0.003875 0.033499 -0.121010
+v -0.003875 0.015357 -0.102028
+v -0.003875 0.009687 -0.124807
+v -0.003875 -0.019795 -0.102028
+v -0.003875 -0.014125 -0.124807
+v -0.003875 -0.036804 -0.121010
+v -0.003875 -0.037938 -0.102028
+v -0.003875 -0.059482 -0.113417
+v -0.003875 -0.068553 -0.083045
+v -0.003875 -0.079893 -0.102028
+v -0.003875 -0.098035 -0.086842
+v -0.003875 -0.092366 -0.060267
+v -0.003875 -0.112776 -0.067859
+v -0.003875 -0.124115 -0.045081
+v -0.003875 -0.108241 -0.029895
+v -0.003875 -0.130919 -0.022302
+v -0.003875 -0.111642 -0.010912
+v -0.003875 -0.134321 0.000477
+v -0.003875 -0.111642 0.023256
+v -0.003875 -0.133187 0.023256
+v -0.003875 -0.127517 0.046035
+v -0.003875 -0.108241 0.042238
+v -0.003875 -0.118446 0.068814
+v -0.003875 -0.092366 0.072610
+v -0.003875 -0.105973 0.087796
+v -0.003875 -0.088964 0.106779
+v -0.003875 -0.068553 0.095389
+v -0.003875 -0.069687 0.118168
+v -0.003875 -0.037938 0.114372
+v -0.003875 -0.048143 0.129557
+v -0.003875 -0.025464 0.137150
+v -0.003875 -0.019795 0.114372
+v -0.003875 -0.001652 0.137150
+v -0.003875 0.015357 0.114372
+v -0.003875 0.022160 0.137150
+v -0.003875 0.033499 0.114372
+v -0.003875 0.044838 0.129557
+v -0.003875 0.066383 0.118168
+v -0.003875 0.064115 0.095389
+v -0.003875 0.085660 0.106779
+v -0.003875 0.089061 0.072610
+v -0.003875 0.101535 0.087796
+v -0.003875 0.115141 0.068814
+v -0.003875 0.104936 0.042238
+v -0.003875 0.124213 0.046035
+v -0.003875 0.107204 0.023256
+v -0.003875 0.128749 0.023256
+v -0.003875 0.129883 0.000477
+v -0.003875 0.107204 -0.010912
+v -0.003875 0.127615 -0.022302
+v -0.003875 0.104936 -0.029895
+v -0.003875 0.119677 -0.045081
+v -0.003875 0.089061 -0.060267
+v -0.003875 0.108338 -0.067859
+v -0.003875 0.093597 -0.086842
+v -0.012086 -0.068553 -0.083045
+v -0.012086 -0.079893 -0.102028
+v -0.012086 -0.098035 -0.086842
+v -0.012086 -0.059482 -0.113417
+v -0.012086 0.033499 -0.121010
+v -0.012086 0.015357 -0.102028
+v -0.012086 0.033499 -0.102028
+v -0.012086 0.009687 -0.124807
+v -0.012086 -0.019795 -0.102028
+v -0.012086 -0.014125 -0.124807
+v -0.012086 -0.036804 -0.121010
+v -0.012086 -0.037938 -0.102028
+v -0.012086 0.119677 -0.045081
+v -0.012086 0.104936 -0.029895
+v -0.012086 0.127615 -0.022302
+v -0.012086 0.089061 -0.060267
+v -0.012086 0.108338 -0.067859
+v -0.012086 0.093597 -0.086842
+v -0.012086 0.064115 -0.083045
+v -0.012086 0.075454 -0.102028
+v -0.012086 0.055044 -0.113417
+v -0.012086 -0.111642 0.023256
+v -0.012086 -0.133187 0.023256
+v -0.012086 -0.127517 0.046035
+v -0.012086 -0.134321 0.000477
+v -0.012086 -0.111642 -0.010912
+v -0.012086 -0.130919 -0.022302
+v -0.012086 -0.108241 -0.029895
+v -0.012086 -0.124115 -0.045081
+v -0.012086 -0.092366 -0.060267
+v -0.012086 -0.112776 -0.067859
+v -0.012086 -0.048143 0.129557
+v -0.012086 -0.037938 0.114372
+v -0.012086 -0.069687 0.118168
+v -0.012086 -0.068553 0.095389
+v -0.012086 -0.088964 0.106779
+v -0.012086 -0.092366 0.072610
+v -0.012086 -0.105973 0.087796
+v -0.012086 -0.118446 0.068814
+v -0.012086 -0.108241 0.042238
+v -0.012086 0.085660 0.106779
+v -0.012086 0.064115 0.095389
+v -0.012086 0.066383 0.118168
+v -0.012086 0.033499 0.114372
+v -0.012086 0.044838 0.129557
+v -0.012086 0.022160 0.137150
+v -0.012086 0.015357 0.114372
+v -0.012086 -0.001652 0.137150
+v -0.012086 -0.019795 0.114372
+v -0.012086 -0.025464 0.137150
+v -0.012086 0.129883 0.000477
+v -0.012086 0.107204 -0.010912
+v -0.012086 0.107204 0.023256
+v -0.012086 0.128749 0.023256
+v -0.012086 0.124213 0.046035
+v -0.012086 0.104936 0.042238
+v -0.012086 0.115141 0.068814
+v -0.012086 0.089061 0.072610
+v -0.012086 0.101535 0.087796
+v 0.104512 -0.012992 -0.045081
+v 0.104512 -0.253383 0.323178
+v 0.104512 -0.253383 0.338364
+v 0.104512 -0.214829 0.349753
+v 0.104512 -0.228436 0.353550
+v -0.025772 0.013089 0.038442
+v -0.025772 0.036901 0.030849
+v -0.025772 0.237605 -0.375374
+v -0.025772 -0.023197 0.015663
+v -0.025772 -0.030000 -0.007116
+v -0.025772 0.016491 -0.079249
+v -0.023582 0.023294 0.008070
+v -0.023582 -0.027732 0.008070
+v -0.023582 -0.001652 -0.018505
+v -0.014823 -0.001652 -0.018505
+v -0.014823 -0.027732 0.008070
+v -0.014823 0.023294 0.008070
+v 0.125160 -0.222896 0.349052
+v 0.114613 0.040917 -0.010804
+v 0.125138 -0.249298 0.330665
+v 0.114555 0.000695 -0.037071
+v 0.104789 0.010540 -0.047958
+v 0.104863 0.044092 -0.021738
+v 0.105222 -0.004475 0.068381
+v 0.104828 0.048473 0.000179
+v -0.032094 0.029848 0.030296
+v -0.045838 0.206063 -0.382322
+v -0.045855 0.234665 -0.367596
+v -0.032086 -0.024880 0.000353
+v -0.026323 0.198532 -0.382402
+v -0.026245 0.210357 -0.389679
+v -0.026324 0.237935 -0.360407
+v -0.026462 0.171191 -0.239026
+v -0.022582 -0.001652 0.201691
+v -0.022582 -0.015259 0.213080
+v -0.022582 -0.026599 0.197894
+v -0.022582 -0.027732 0.163726
+v -0.022582 -0.041340 0.209283
+v -0.022582 -0.051545 0.194098
+v -0.022582 -0.115044 0.178912
+v -0.022582 -0.118446 0.163726
+v -0.022582 -0.096902 0.175115
+v -0.022582 -0.096902 0.137150
+v -0.022582 -0.052679 0.159929
+v -0.022582 -0.075357 0.186505
+v -0.022582 -0.067420 0.201691
+v -0.022582 -0.092366 0.194098
+v -0.022582 -0.136589 0.163726
+v -0.022582 -0.137723 0.144743
+v -0.022582 -0.132053 0.099186
+v -0.022582 -0.153598 0.125761
+v -0.022582 -0.168338 0.106779
+v -0.022582 -0.171740 0.125761
+v -0.022582 -0.155865 0.144743
+v -0.022582 -0.185347 0.102982
+v -0.022582 -0.179678 0.084000
+v -0.022582 -0.154731 0.057424
+v -0.022582 -0.188749 0.061221
+v -0.022582 -0.158133 0.030849
+v -0.022582 -0.194419 0.038442
+v -0.022582 -0.196686 0.011867
+v -0.022582 -0.208026 0.027052
+v -0.022582 -0.196686 0.076407
+v -0.022582 -0.204624 0.053628
+v -0.022582 -0.209160 0.000477
+v -0.022582 -0.195553 -0.010912
+v -0.022582 -0.158133 -0.018505
+v -0.022582 -0.001652 0.030849
+v -0.022582 -0.206892 -0.026098
+v -0.022582 -0.192151 -0.037488
+v -0.022582 -0.154731 -0.045081
+v -0.022582 -0.179678 -0.102028
+v -0.022582 -0.161535 -0.105824
+v -0.022582 -0.174008 -0.083045
+v -0.022582 -0.132053 -0.090638
+v -0.022582 -0.184213 -0.060267
+v -0.022582 -0.201222 -0.052674
+v -0.022582 -0.191017 -0.079249
+v -0.022582 -0.163803 -0.124807
+v -0.022582 -0.145660 -0.124807
+v -0.022582 -0.096901 -0.124807
+v -0.022582 -0.128651 -0.139993
+v -0.022582 -0.108241 -0.155178
+v -0.022582 -0.126383 -0.158975
+v -0.022582 -0.145660 -0.143789
+v -0.022582 -0.103705 -0.174161
+v -0.022582 -0.086696 -0.170364
+v -0.022582 -0.052679 -0.147585
+v -0.022582 -0.062884 -0.177957
+v -0.022582 -0.039071 -0.185550
+v -0.022582 -0.054946 -0.193143
+v -0.022582 -0.079893 -0.185550
+v -0.022582 -0.027732 -0.151382
+v -0.022582 -0.028866 -0.200736
+v -0.022582 -0.014125 -0.189347
+v -0.022582 0.010821 -0.189347
+v -0.022582 0.023294 -0.151382
+v -0.022582 0.035767 -0.185550
+v -0.022582 0.048240 -0.147585
+v -0.022582 0.059580 -0.177957
+v -0.022582 0.082258 -0.170364
+v -0.022582 0.075454 -0.185550
+v -0.022582 0.050508 -0.193143
+v -0.022582 -0.001652 -0.200736
+v -0.022582 0.024428 -0.200736
+v -0.022582 0.099267 -0.174161
+v -0.022582 0.103802 -0.155178
+v -0.022582 0.092463 -0.124807
+v -0.022582 0.121945 -0.158975
+v -0.022582 0.124213 -0.139993
+v -0.022582 0.142356 -0.124807
+v -0.022582 0.127615 -0.090638
+v -0.022582 0.157097 -0.105824
+v -0.022582 0.170704 -0.083045
+v -0.022582 0.175239 -0.102028
+v -0.022582 0.142356 -0.143789
+v -0.022582 0.160498 -0.124807
+v -0.022582 0.187713 -0.079249
+v -0.022582 0.180909 -0.060267
+v -0.022582 0.150293 -0.045081
+v -0.022582 0.196784 -0.052674
+v -0.022582 0.187713 -0.037488
+v -0.022582 0.154829 -0.018505
+v -0.022582 0.202453 -0.026098
+v -0.022582 0.191114 -0.010912
+v -0.022582 0.204721 0.000477
+v -0.022582 0.192248 0.011867
+v -0.022582 0.154829 0.030849
+v -0.022582 0.189980 0.038442
+v -0.022582 0.184311 0.061221
+v -0.022582 0.200186 0.053628
+v -0.022582 0.204721 0.027052
+v -0.022582 0.192248 0.076407
+v -0.022582 0.176373 0.084000
+v -0.022582 0.182043 0.102982
+v -0.022582 0.163900 0.106779
+v -0.022582 0.150293 0.057424
+v -0.022582 0.127615 0.099186
+v -0.022582 0.150293 0.125761
+v -0.022582 0.168436 0.125761
+v -0.022582 0.151427 0.144743
+v -0.022582 0.133284 0.144743
+v -0.022582 0.092463 0.137150
+v -0.022582 0.114008 0.163726
+v -0.022582 0.093597 0.175115
+v -0.022582 0.110606 0.178912
+v -0.022582 0.132150 0.163726
+v -0.022582 0.087928 0.194098
+v -0.022582 0.070919 0.186505
+v -0.022582 0.048240 0.159929
+v -0.022582 0.062981 0.201691
+v -0.022582 0.047106 0.194098
+v -0.022582 0.023294 0.163726
+v -0.022582 0.023294 0.197894
+v -0.022582 0.010821 0.213080
+v -0.022582 0.038035 0.209283
+v -0.013823 -0.179678 0.084000
+v -0.013823 -0.168338 0.106779
+v -0.013823 -0.185347 0.102982
+v -0.013823 -0.196686 0.076407
+v -0.013823 -0.188749 0.061221
+v -0.013823 -0.194419 0.038442
+v -0.013823 -0.204624 0.053628
+v -0.013823 -0.208026 0.027052
+v -0.013823 -0.196686 0.011867
+v -0.013823 -0.158133 0.030849
+v -0.013823 -0.154731 0.057424
+v -0.013823 -0.132053 0.099186
+v -0.013823 -0.153598 0.125761
+v -0.013823 -0.171740 0.125761
+v -0.013823 -0.137723 0.144743
+v -0.013823 -0.155865 0.144743
+v -0.013823 -0.096902 0.137150
+v -0.013823 -0.158133 -0.018505
+v -0.013823 -0.001652 0.030849
+v -0.013823 -0.201222 -0.052674
+v -0.013823 -0.184213 -0.060267
+v -0.013823 -0.192151 -0.037488
+v -0.013823 -0.154731 -0.045081
+v -0.013823 -0.195553 -0.010912
+v -0.013823 -0.209160 0.000477
+v -0.013823 -0.206892 -0.026098
+v -0.013823 -0.174008 -0.083045
+v -0.013823 -0.191017 -0.079249
+v -0.013823 -0.132053 -0.090638
+v -0.013823 -0.128651 -0.139993
+v -0.013823 -0.145660 -0.124807
+v -0.013823 -0.145660 -0.143789
+v -0.013823 -0.096901 -0.124807
+v -0.013823 -0.161535 -0.105824
+v -0.013823 -0.179678 -0.102028
+v -0.013823 -0.163803 -0.124807
+v -0.013823 -0.054946 -0.193143
+v -0.013823 -0.039071 -0.185550
+v -0.013823 -0.062884 -0.177957
+v -0.013823 -0.052679 -0.147585
+v -0.013823 -0.086696 -0.170364
+v -0.013823 -0.108241 -0.155178
+v -0.013823 -0.126383 -0.158975
+v -0.013823 -0.103705 -0.174161
+v -0.013823 -0.079893 -0.185550
+v -0.013823 -0.014125 -0.189347
+v -0.013823 -0.028866 -0.200736
+v -0.013823 -0.027732 -0.151382
+v -0.013823 -0.001652 -0.200736
+v -0.013823 0.010821 -0.189347
+v -0.013823 0.023294 -0.151382
+v -0.013823 0.035767 -0.185550
+v -0.013823 0.024428 -0.200736
+v -0.013823 0.048240 -0.147585
+v -0.013823 0.103802 -0.155178
+v -0.013823 0.082258 -0.170364
+v -0.013823 0.099267 -0.174161
+v -0.013823 0.092463 -0.124807
+v -0.013823 0.059580 -0.177957
+v -0.013823 0.050508 -0.193143
+v -0.013823 0.075454 -0.185550
+v -0.013823 0.160498 -0.124807
+v -0.013823 0.157097 -0.105824
+v -0.013823 0.142356 -0.124807
+v -0.013823 0.127615 -0.090638
+v -0.013823 0.124213 -0.139993
+v -0.013823 0.121945 -0.158975
+v -0.013823 0.142356 -0.143789
+v -0.013823 0.175239 -0.102028
+v -0.013823 0.170704 -0.083045
+v -0.013823 0.150293 -0.045081
+v -0.013823 0.191114 -0.010912
+v -0.013823 0.187713 -0.037488
+v -0.013823 0.202453 -0.026098
+v -0.013823 0.154829 -0.018505
+v -0.013823 0.180909 -0.060267
+v -0.013823 0.187713 -0.079249
+v -0.013823 0.196784 -0.052674
+v -0.013823 0.192248 0.011867
+v -0.013823 0.204721 0.000477
+v -0.013823 0.154829 0.030849
+v -0.013823 0.163900 0.106779
+v -0.013823 0.176373 0.084000
+v -0.013823 0.182043 0.102982
+v -0.013823 0.127615 0.099186
+v -0.013823 0.150293 0.057424
+v -0.013823 0.184311 0.061221
+v -0.013823 0.189980 0.038442
+v -0.013823 0.204721 0.027052
+v -0.013823 0.192248 0.076407
+v -0.013823 0.200186 0.053628
+v -0.013823 0.132150 0.163726
+v -0.013823 0.114008 0.163726
+v -0.013823 0.133284 0.144743
+v -0.013823 0.092463 0.137150
+v -0.013823 0.150293 0.125761
+v -0.013823 0.168436 0.125761
+v -0.013823 0.151427 0.144743
+v -0.013823 0.110606 0.178912
+v -0.013823 0.093597 0.175115
+v -0.013823 0.048240 0.159929
+v -0.013823 0.010821 0.213080
+v -0.013823 -0.001652 0.201691
+v -0.013823 0.023294 0.197894
+v -0.013823 0.023294 0.163726
+v -0.013823 0.047106 0.194098
+v -0.013823 0.070919 0.186505
+v -0.013823 0.087928 0.194098
+v -0.013823 0.038035 0.209283
+v -0.013823 0.062981 0.201691
+v -0.013823 -0.026599 0.197894
+v -0.013823 -0.015259 0.213080
+v -0.013823 -0.027732 0.163726
+v -0.013823 -0.051545 0.194098
+v -0.013823 -0.041340 0.209283
+v -0.013823 -0.052679 0.159929
+v -0.013823 -0.067420 0.201691
+v -0.013823 -0.075357 0.186505
+v -0.013823 -0.096902 0.175115
+v -0.013823 -0.118446 0.163726
+v -0.013823 -0.136589 0.163726
+v -0.013823 -0.092366 0.194098
+v -0.013823 -0.115044 0.178912
+v -0.002875 0.075454 -0.102028
+v -0.002875 0.064115 -0.083045
+v -0.002875 0.055044 -0.113417
+v -0.002875 0.033499 -0.102028
+v -0.002875 0.033499 -0.121010
+v -0.002875 0.015357 -0.102028
+v -0.002875 0.009687 -0.124807
+v -0.002875 -0.019795 -0.102028
+v -0.002875 -0.014125 -0.124807
+v -0.002875 -0.036804 -0.121010
+v -0.002875 -0.037938 -0.102028
+v -0.002875 -0.059482 -0.113417
+v -0.002875 -0.068553 -0.083045
+v -0.002875 -0.079893 -0.102028
+v -0.002875 -0.098035 -0.086842
+v -0.002875 -0.092366 -0.060267
+v -0.002875 -0.112776 -0.067859
+v -0.002875 -0.124115 -0.045081
+v -0.002875 -0.108241 -0.029895
+v -0.002875 -0.130919 -0.022302
+v -0.002875 -0.111642 -0.010912
+v -0.002875 -0.134321 0.000477
+v -0.002875 -0.111642 0.023256
+v -0.002875 -0.133187 0.023256
+v -0.002875 -0.127517 0.046035
+v -0.002875 -0.108241 0.042238
+v -0.002875 -0.118446 0.068814
+v -0.002875 -0.092366 0.072610
+v -0.002875 -0.105973 0.087796
+v -0.002875 -0.088964 0.106779
+v -0.002875 -0.068553 0.095389
+v -0.002875 -0.069687 0.118168
+v -0.002875 -0.037938 0.114372
+v -0.002875 -0.048143 0.129557
+v -0.002875 -0.025464 0.137150
+v -0.002875 -0.019795 0.114372
+v -0.002875 -0.001652 0.137150
+v -0.002875 0.015357 0.114372
+v -0.002875 0.022160 0.137150
+v -0.002875 0.033499 0.114372
+v -0.002875 0.044838 0.129557
+v -0.002875 0.066383 0.118168
+v -0.002875 0.064115 0.095389
+v -0.002875 0.085660 0.106779
+v -0.002875 0.089061 0.072610
+v -0.002875 0.101535 0.087796
+v -0.002875 0.115141 0.068814
+v -0.002875 0.104936 0.042238
+v -0.002875 0.124213 0.046035
+v -0.002875 0.107204 0.023256
+v -0.002875 0.128749 0.023256
+v -0.002875 0.129883 0.000477
+v -0.002875 0.107204 -0.010912
+v -0.002875 0.127615 -0.022302
+v -0.002875 0.104936 -0.029895
+v -0.002875 0.119677 -0.045081
+v -0.002875 0.089061 -0.060267
+v -0.002875 0.108338 -0.067859
+v -0.002875 0.093597 -0.086842
+v -0.011086 -0.068553 -0.083045
+v -0.011086 -0.098035 -0.086842
+v -0.011086 -0.079893 -0.102028
+v -0.011086 -0.059482 -0.113417
+v -0.011086 0.033499 -0.121010
+v -0.011086 0.033499 -0.102028
+v -0.011086 0.015357 -0.102028
+v -0.011086 0.009687 -0.124807
+v -0.011086 -0.019795 -0.102028
+v -0.011086 -0.014125 -0.124807
+v -0.011086 -0.036804 -0.121010
+v -0.011086 -0.037938 -0.102028
+v -0.011086 0.119677 -0.045081
+v -0.011086 0.127615 -0.022302
+v -0.011086 0.104936 -0.029895
+v -0.011086 0.089061 -0.060267
+v -0.011086 0.108338 -0.067859
+v -0.011086 0.093597 -0.086842
+v -0.011086 0.064115 -0.083045
+v -0.011086 0.075454 -0.102028
+v -0.011086 0.055044 -0.113417
+v -0.011086 -0.111642 0.023256
+v -0.011086 -0.127517 0.046035
+v -0.011086 -0.133187 0.023256
+v -0.011086 -0.134321 0.000477
+v -0.011086 -0.111642 -0.010912
+v -0.011086 -0.130919 -0.022302
+v -0.011086 -0.108241 -0.029895
+v -0.011086 -0.124115 -0.045081
+v -0.011086 -0.092366 -0.060267
+v -0.011086 -0.112776 -0.067859
+v -0.011086 -0.048143 0.129557
+v -0.011086 -0.069687 0.118168
+v -0.011086 -0.037938 0.114372
+v -0.011086 -0.068553 0.095389
+v -0.011086 -0.088964 0.106779
+v -0.011086 -0.092366 0.072610
+v -0.011086 -0.105973 0.087796
+v -0.011086 -0.118446 0.068814
+v -0.011086 -0.108241 0.042238
+v -0.011086 0.085660 0.106779
+v -0.011086 0.066383 0.118168
+v -0.011086 0.064115 0.095389
+v -0.011086 0.033499 0.114372
+v -0.011086 0.044838 0.129557
+v -0.011086 0.022160 0.137150
+v -0.011086 0.015357 0.114372
+v -0.011086 -0.001652 0.137150
+v -0.011086 -0.019795 0.114372
+v -0.011086 -0.025464 0.137150
+v -0.011086 0.129883 0.000477
+v -0.011086 0.107204 -0.010912
+v -0.011086 0.107204 0.023256
+v -0.011086 0.128749 0.023256
+v -0.011086 0.124213 0.046035
+v -0.011086 0.104936 0.042238
+v -0.011086 0.115141 0.068814
+v -0.011086 0.089061 0.072610
+v -0.011086 0.101535 0.087796
+v 0.104776 -0.012405 -0.044315
+v 0.105055 -0.252595 0.323467
+v 0.105010 -0.252645 0.337909
+v 0.105055 -0.228276 0.352725
+v 0.105068 -0.215336 0.349094
+v -0.025987 0.013367 0.037506
+v -0.026167 0.036240 0.030211
+v -0.026269 0.236910 -0.374855
+v -0.026034 -0.022537 0.014959
+v -0.026116 -0.029090 -0.006886
+v -0.026563 0.017006 -0.078917
+v -0.022582 0.023294 0.008070
+v -0.022582 -0.027732 0.008070
+v -0.022582 -0.001652 -0.018505
+v -0.013823 -0.001652 -0.018505
+v -0.013823 -0.027732 0.008070
+v -0.013823 0.023294 0.008070
+# 794 vertices, 0 vertices normals
+
+f 1 2 3
+f 3 2 4
+f 5 6 7
+f 6 8 7
+f 9 10 11
+f 12 9 11
+f 11 13 14
+f 10 15 16
+f 17 18 19
+f 20 18 17
+f 18 21 22
+f 23 24 25
+f 24 26 25
+f 26 24 27
+f 24 28 27
+f 21 27 28
+f 29 21 28
+f 24 30 28
+f 31 25 32
+f 25 26 32
+f 32 26 33
+f 34 32 33
+f 34 33 35
+f 36 34 35
+f 32 34 37
+f 35 38 39
+f 35 33 38
+f 33 40 38
+f 38 40 41
+f 41 40 42
+f 43 41 42
+f 43 42 44
+f 45 43 44
+f 46 38 41
+f 41 43 47
+f 44 48 49
+f 48 44 50
+f 44 42 50
+f 42 51 50
+f 48 52 53
+f 48 50 52
+f 50 54 52
+f 55 56 57
+f 56 58 57
+f 54 58 56
+f 59 54 56
+f 52 54 59
+f 60 52 59
+f 59 56 61
+f 62 57 63
+f 57 58 63
+f 58 64 63
+f 64 65 63
+f 65 64 66
+f 67 65 66
+f 63 65 68
+f 66 69 70
+f 66 64 69
+f 64 71 69
+f 69 71 72
+f 72 71 73
+f 74 72 73
+f 75 69 72
+f 71 76 73
+f 73 77 78
+f 76 77 73
+f 77 76 79
+f 76 80 79
+f 80 81 79
+f 80 82 81
+f 82 83 81
+f 83 82 84
+f 85 83 84
+f 81 83 86
+f 87 77 79
+f 79 81 88
+f 84 89 90
+f 91 89 84
+f 82 91 84
+f 92 89 93
+f 89 91 93
+f 93 91 94
+f 91 95 94
+f 94 95 96
+f 96 95 97
+f 98 96 97
+f 93 94 99
+f 100 94 96
+f 97 101 102
+f 103 101 97
+f 95 103 97
+f 104 101 105
+f 101 103 105
+f 103 106 105
+f 105 107 108
+f 107 109 110
+f 109 107 106
+f 111 109 106
+f 109 111 112
+f 112 111 113
+f 112 113 114
+f 115 109 112
+f 116 113 117
+f 117 118 119
+f 111 120 113
+f 113 120 117
+f 120 121 117
+f 121 118 117
+f 118 121 122
+f 123 118 122
+f 122 124 125
+f 122 121 124
+f 121 126 124
+f 124 126 127
+f 127 126 128
+f 129 127 128
+f 130 124 127
+f 128 131 132
+f 133 131 128
+f 126 133 128
+f 134 131 135
+f 131 133 135
+f 133 136 135
+f 136 137 135
+f 137 136 17
+f 138 137 17
+f 135 137 139
+f 140 141 142
+f 143 140 144
+f 145 146 144
+f 147 145 148
+f 148 145 149
+f 145 144 149
+f 149 144 150
+f 144 140 150
+f 150 140 151
+f 151 140 142
+f 142 152 151
+f 153 152 142
+f 152 154 155
+f 152 155 151
+f 151 155 156
+f 149 157 158
+f 149 158 148
+f 159 160 161
+f 161 160 162
+f 162 160 158
+f 158 160 163
+f 148 158 163
+f 163 164 148
+f 160 165 163
+f 166 167 161
+f 162 166 161
+f 168 166 162
+f 169 170 171
+f 169 171 172
+f 172 171 168
+f 171 173 168
+f 173 166 168
+f 174 166 173
+f 175 173 171
+f 176 177 178
+f 178 177 179
+f 177 180 179
+f 180 172 179
+f 181 172 180
+f 181 169 172
+f 182 169 181
+f 180 183 181
+f 184 180 177
+f 185 186 178
+f 185 178 187
+f 187 178 179
+f 188 185 189
+f 189 185 187
+f 190 189 187
+f 191 192 189
+f 191 189 190
+f 190 193 191
+f 194 195 196
+f 194 196 197
+f 197 196 193
+f 196 198 193
+f 191 193 198
+f 198 199 191
+f 200 198 196
+f 201 202 203
+f 203 202 204
+f 202 197 204
+f 205 197 202
+f 205 194 197
+f 206 194 205
+f 202 207 205
+f 208 203 209
+f 209 203 204
+f 210 209 204
+f 211 212 213
+f 211 213 214
+f 214 213 210
+f 213 215 210
+f 215 209 210
+f 215 216 209
+f 217 215 213
+f 218 219 211
+f 211 214 218
+f 218 214 220
+f 221 222 223
+f 221 223 224
+f 224 223 225
+f 223 226 225
+f 226 220 225
+f 227 220 226
+f 227 218 220
+f 228 218 227
+f 229 226 223
+f 226 230 227
+f 231 232 233
+f 233 232 234
+f 232 224 234
+f 235 224 232
+f 235 221 224
+f 236 221 235
+f 232 237 235
+f 238 233 239
+f 239 233 234
+f 240 239 234
+f 241 242 243
+f 243 242 244
+f 242 245 244
+f 244 245 240
+f 245 246 240
+f 246 239 240
+f 246 247 239
+f 242 248 245
+f 249 246 245
+f 250 251 243
+f 250 243 252
+f 252 243 244
+f 253 254 250
+f 250 252 253
+f 253 252 255
+f 256 253 257
+f 257 253 255
+f 257 255 258
+f 258 255 156
+f 156 259 258
+f 155 259 156
+f 260 259 155
+f 258 261 257
+f 258 259 262
+f 263 264 265
+f 265 264 266
+f 266 264 267
+f 268 266 267
+f 269 268 267
+f 270 268 269
+f 269 271 270
+f 272 270 271
+f 273 270 272
+f 272 274 273
+f 274 275 273
+f 276 275 274
+f 277 275 276
+f 278 275 277
+f 277 279 278
+f 279 280 278
+f 278 280 281
+f 280 282 281
+f 282 283 281
+f 282 284 283
+f 283 284 285
+f 284 286 285
+f 286 287 285
+f 285 287 288
+f 289 288 287
+f 290 288 289
+f 289 291 290
+f 291 292 290
+f 290 292 293
+f 292 294 293
+f 293 294 295
+f 295 294 296
+f 295 296 297
+f 298 295 297
+f 297 299 298
+f 298 299 300
+f 300 299 301
+f 300 301 302
+f 302 301 303
+f 304 302 303
+f 305 302 304
+f 304 306 305
+f 305 306 307
+f 307 306 308
+f 308 309 307
+f 307 309 310
+f 310 309 311
+f 310 311 312
+f 312 311 313
+f 313 314 312
+f 312 314 315
+f 316 315 314
+f 317 315 316
+f 316 318 317
+f 319 317 318
+f 319 318 320
+f 320 321 319
+f 319 321 265
+f 265 321 263
+f 322 323 324
+f 323 322 325
+f 326 327 328
+f 326 329 327
+f 329 330 327
+f 331 330 329
+f 331 332 330
+f 332 333 330
+f 334 335 336
+f 334 337 335
+f 338 337 334
+f 339 337 338
+f 337 339 340
+f 339 341 340
+f 341 342 340
+f 342 328 340
+f 326 328 342
+f 343 344 345
+f 344 343 346
+f 343 347 346
+f 347 348 346
+f 349 348 347
+f 348 349 350
+f 349 351 350
+f 351 352 350
+f 352 351 324
+f 351 322 324
+f 353 354 355
+f 354 356 355
+f 355 356 357
+f 356 358 357
+f 358 359 357
+f 358 360 359
+f 358 361 360
+f 362 363 364
+f 364 363 365
+f 366 364 365
+f 367 366 365
+f 368 367 365
+f 367 368 369
+f 368 370 369
+f 369 370 371
+f 371 370 354
+f 371 354 353
+f 372 336 373
+f 372 373 374
+f 375 372 374
+f 375 374 376
+f 374 377 376
+f 378 376 377
+f 379 378 377
+f 378 379 380
+f 362 380 379
+f 363 362 379
+f 381 4 382
+f 382 4 2
+f 383 382 2
+f 1 384 385
+f 383 1 385
+f 2 1 383
+f 5 3 4
+f 5 4 381
+f 8 3 7
+f 7 3 5
+f 3 8 1
+f 8 6 1
+f 6 384 1
+f 385 384 383
+f 382 383 384
+f 6 382 384
+f 381 382 6
+f 5 381 6
+f 386 387 9
+f 388 10 16
+f 10 388 11
+f 386 9 12
+f 389 386 12
+f 12 390 389
+f 388 13 11
+f 12 11 390
+f 390 11 391
+f 391 11 14
+f 9 387 10
+f 387 15 10
+f 388 16 15
+f 388 15 13
+f 13 15 14
+f 14 15 391
+f 391 15 387
+f 386 391 387
+f 386 389 391
+f 391 389 390
+f 392 393 20
+f 136 20 17
+f 136 392 20
+f 27 21 20
+f 21 18 20
+f 51 394 50
+f 106 107 105
+f 111 106 51
+f 106 394 51
+f 76 393 80
+f 393 392 80
+f 158 157 395
+f 187 396 190
+f 190 396 397
+f 220 214 157
+f 157 214 395
+f 244 397 252
+f 252 397 396
+f 322 333 325
+f 333 332 325
+f 336 335 373
+f 361 345 360
+f 361 343 345
+f 398 399 400
+f 399 401 400
+f 402 403 404
+f 404 403 405
+f 406 407 408
+f 409 407 406
+f 407 410 411
+f 408 412 413
+f 414 415 416
+f 417 414 416
+f 416 418 419
+f 420 421 422
+f 422 421 423
+f 423 424 422
+f 422 424 425
+f 419 425 424
+f 426 425 419
+f 422 425 427
+f 428 429 421
+f 421 429 423
+f 429 430 423
+f 431 430 429
+f 431 432 430
+f 433 432 431
+f 429 434 431
+f 432 435 436
+f 432 436 430
+f 430 436 437
+f 436 438 437
+f 438 439 437
+f 440 439 438
+f 440 441 439
+f 442 441 440
+f 443 438 436
+f 438 444 440
+f 441 445 446
+f 446 447 441
+f 441 447 439
+f 439 447 448
+f 446 449 450
+f 446 450 447
+f 447 450 451
+f 452 453 454
+f 454 453 455
+f 451 454 455
+f 456 454 451
+f 450 456 451
+f 457 456 450
+f 456 458 454
+f 459 460 453
+f 453 460 455
+f 455 460 461
+f 461 460 462
+f 462 463 461
+f 464 463 462
+f 460 465 462
+f 463 466 467
+f 463 467 461
+f 461 467 468
+f 467 469 468
+f 469 470 468
+f 471 470 469
+f 472 469 467
+f 468 470 473
+f 470 474 475
+f 473 470 475
+f 475 476 473
+f 473 476 477
+f 477 476 478
+f 477 478 479
+f 479 478 480
+f 480 481 479
+f 482 481 480
+f 478 483 480
+f 484 476 475
+f 476 485 478
+f 481 486 487
+f 488 481 487
+f 479 481 488
+f 489 490 487
+f 487 490 488
+f 490 491 488
+f 488 491 492
+f 491 493 492
+f 493 494 492
+f 495 494 493
+f 490 496 491
+f 497 493 491
+f 494 498 499
+f 500 494 499
+f 492 494 500
+f 501 502 499
+f 499 502 500
+f 500 502 503
+f 502 504 505
+f 505 506 507
+f 507 503 505
+f 508 503 507
+f 507 509 508
+f 509 510 508
+f 509 511 510
+f 512 509 507
+f 513 514 510
+f 514 515 516
+f 508 510 517
+f 510 514 517
+f 517 514 518
+f 518 514 516
+f 516 519 518
+f 520 519 516
+f 519 521 522
+f 519 522 518
+f 518 522 523
+f 522 524 523
+f 524 525 523
+f 526 525 524
+f 527 524 522
+f 525 528 529
+f 530 525 529
+f 523 525 530
+f 531 532 529
+f 529 532 530
+f 530 532 533
+f 533 532 534
+f 534 414 533
+f 535 414 534
+f 532 536 534
+f 537 538 539
+f 540 541 537
+f 542 541 543
+f 544 545 542
+f 545 546 542
+f 542 546 541
+f 546 547 541
+f 541 547 537
+f 547 548 537
+f 548 538 537
+f 538 548 549
+f 550 538 549
+f 549 551 552
+f 549 548 551
+f 548 553 551
+f 546 554 555
+f 546 545 554
+f 556 557 558
+f 557 559 558
+f 559 554 558
+f 554 560 558
+f 545 560 554
+f 560 545 561
+f 558 560 562
+f 563 557 564
+f 559 557 563
+f 565 559 563
+f 566 567 568
+f 566 569 567
+f 569 565 567
+f 567 565 570
+f 570 565 563
+f 571 570 563
+f 572 567 570
+f 573 574 575
+f 574 576 575
+f 575 576 577
+f 577 576 569
+f 578 577 569
+f 578 569 566
+f 579 578 566
+f 577 578 580
+f 581 575 577
+f 582 574 583
+f 582 584 574
+f 584 576 574
+f 585 586 582
+f 586 584 582
+f 587 584 586
+f 588 586 589
+f 588 587 586
+f 587 588 590
+f 591 592 593
+f 591 594 592
+f 594 590 592
+f 592 590 595
+f 588 595 590
+f 595 588 596
+f 597 592 595
+f 598 599 600
+f 599 601 600
+f 600 601 594
+f 602 600 594
+f 602 594 591
+f 603 602 591
+f 600 602 604
+f 605 606 599
+f 606 601 599
+f 607 601 606
+f 608 609 610
+f 608 611 609
+f 611 607 609
+f 609 607 612
+f 612 607 606
+f 612 606 613
+f 614 609 612
+f 615 608 616
+f 608 615 611
+f 615 617 611
+f 618 619 620
+f 618 621 619
+f 621 622 619
+f 619 622 623
+f 623 622 617
+f 624 623 617
+f 624 617 615
+f 625 624 615
+f 626 619 623
+f 623 624 627
+f 628 629 630
+f 629 631 630
+f 630 631 621
+f 632 630 621
+f 632 621 618
+f 633 632 618
+f 630 632 634
+f 635 636 629
+f 636 631 629
+f 637 631 636
+f 638 639 640
+f 639 641 640
+f 640 641 642
+f 641 637 642
+f 642 637 643
+f 643 637 636
+f 643 636 644
+f 640 642 645
+f 646 642 643
+f 647 639 648
+f 647 649 639
+f 649 641 639
+f 650 647 651
+f 647 650 649
+f 650 652 649
+f 653 654 650
+f 654 652 650
+f 654 655 652
+f 655 553 652
+f 553 655 656
+f 551 553 656
+f 657 551 656
+f 655 654 658
+f 655 659 656
+f 660 661 662
+f 661 663 662
+f 663 664 662
+f 665 664 663
+f 666 664 665
+f 667 666 665
+f 666 667 668
+f 669 668 667
+f 670 669 667
+f 669 670 671
+f 671 670 672
+f 673 671 672
+f 674 673 672
+f 675 674 672
+f 674 675 676
+f 676 675 677
+f 675 678 677
+f 677 678 679
+f 679 678 680
+f 679 680 681
+f 680 682 681
+f 681 682 683
+f 683 682 684
+f 682 685 684
+f 686 684 685
+f 687 686 685
+f 686 687 688
+f 688 687 689
+f 687 690 689
+f 689 690 691
+f 690 692 691
+f 692 693 691
+f 692 694 693
+f 695 694 692
+f 694 695 696
+f 695 697 696
+f 697 698 696
+f 697 699 698
+f 699 700 698
+f 701 700 699
+f 702 701 699
+f 701 702 703
+f 702 704 703
+f 704 705 703
+f 705 704 706
+f 704 707 706
+f 707 708 706
+f 707 709 708
+f 709 710 708
+f 710 709 711
+f 709 712 711
+f 713 711 712
+f 714 713 712
+f 713 714 715
+f 716 715 714
+f 716 717 715
+f 717 716 718
+f 716 661 718
+f 661 660 718
+f 719 720 721
+f 721 722 719
+f 723 724 725
+f 723 725 726
+f 726 725 727
+f 728 726 727
+f 728 727 729
+f 729 727 730
+f 731 732 733
+f 731 733 734
+f 735 731 734
+f 736 735 734
+f 734 737 736
+f 736 737 738
+f 738 737 739
+f 739 737 724
+f 723 739 724
+f 740 741 742
+f 742 743 740
+f 740 743 744
+f 744 743 745
+f 746 744 745
+f 745 747 746
+f 746 747 748
+f 748 747 749
+f 749 720 748
+f 748 720 719
+f 750 751 752
+f 752 751 753
+f 751 754 753
+f 753 754 755
+f 755 754 756
+f 755 756 757
+f 755 757 758
+f 759 760 761
+f 760 762 761
+f 763 762 760
+f 764 762 763
+f 765 762 764
+f 764 766 765
+f 765 766 767
+f 766 768 767
+f 768 752 767
+f 768 750 752
+f 769 770 732
+f 769 771 770
+f 772 771 769
+f 772 773 771
+f 771 773 774
+f 775 774 773
+f 776 774 775
+f 775 777 776
+f 759 776 777
+f 761 776 759
+f 778 779 401
+f 779 400 401
+f 780 400 779
+f 398 781 782
+f 780 781 398
+f 400 780 398
+f 402 401 399
+f 402 778 401
+f 405 403 399
+f 403 402 399
+f 399 398 405
+f 405 398 404
+f 404 398 782
+f 781 780 782
+f 779 782 780
+f 404 782 779
+f 778 404 779
+f 402 404 778
+f 783 406 784
+f 785 412 408
+f 408 407 785
+f 783 409 406
+f 786 409 783
+f 409 786 787
+f 785 407 411
+f 409 787 407
+f 787 788 407
+f 788 410 407
+f 406 408 784
+f 784 408 413
+f 785 413 412
+f 785 411 413
+f 411 410 413
+f 410 788 413
+f 788 784 413
+f 783 784 788
+f 783 788 786
+f 788 787 786
+f 789 417 790
+f 533 414 417
+f 533 417 789
+f 424 417 419
+f 419 417 416
+f 448 447 791
+f 503 502 505
+f 508 448 503
+f 503 448 791
+f 473 477 790
+f 790 477 789
+f 554 792 555
+f 584 587 793
+f 587 794 793
+f 617 555 611
+f 555 792 611
+f 641 649 794
+f 649 793 794
+f 719 722 730
+f 730 722 729
+f 732 770 733
+f 758 757 741
+f 758 741 740
+f 169 182 579
+f 169 579 566
+f 274 272 669
+f 274 669 671
+f 44 49 445
+f 44 445 441
+f 46 41 438
+f 46 438 443
+f 159 161 557
+f 159 557 556
+f 162 158 554
+f 162 554 559
+f 271 269 666
+f 271 666 668
+f 164 163 560
+f 164 560 561
+f 266 268 665
+f 266 665 663
+f 275 278 675
+f 275 675 672
+f 265 266 663
+f 265 663 661
+f 36 35 432
+f 36 432 433
+f 161 167 564
+f 161 564 557
+f 172 168 565
+f 172 565 569
+f 168 162 559
+f 168 559 565
+f 38 46 443
+f 38 443 436
+f 272 271 668
+f 272 668 669
+f 35 39 435
+f 35 435 432
+f 270 273 670
+f 270 670 667
+f 163 165 562
+f 163 562 560
+f 179 172 569
+f 179 569 576
+f 277 276 673
+f 277 673 674
+f 154 152 549
+f 154 549 552
+f 31 32 429
+f 31 429 428
+f 175 171 567
+f 175 567 572
+f 152 153 550
+f 152 550 549
+f 37 34 431
+f 37 431 434
+f 52 60 457
+f 52 457 450
+f 282 280 677
+f 282 677 679
+f 149 150 547
+f 149 547 546
+f 34 36 433
+f 34 433 431
+f 171 170 568
+f 171 568 567
+f 279 277 674
+f 279 674 676
+f 158 395 792
+f 158 792 554
+f 51 42 439
+f 51 439 448
+f 165 160 558
+f 165 558 562
+f 32 37 434
+f 32 434 429
+f 269 267 664
+f 269 664 666
+f 41 47 444
+f 41 444 438
+f 45 44 441
+f 45 441 442
+f 268 270 667
+f 268 667 665
+f 280 279 676
+f 280 676 677
+f 278 281 678
+f 278 678 675
+f 150 151 548
+f 150 548 547
+f 43 45 442
+f 43 442 440
+f 144 146 543
+f 144 543 541
+f 64 58 455
+f 64 455 461
+f 145 147 544
+f 145 544 542
+f 289 287 684
+f 289 684 686
+f 287 286 683
+f 287 683 684
+f 285 288 685
+f 285 685 682
+f 58 54 451
+f 58 451 455
+f 57 62 459
+f 57 459 453
+f 288 290 687
+f 288 687 685
+f 143 144 541
+f 143 541 540
+f 55 57 453
+f 55 453 452
+f 22 21 419
+f 22 419 418
+f 394 106 503
+f 394 503 791
+f 374 373 770
+f 374 770 771
+f 61 56 454
+f 61 454 458
+f 56 55 452
+f 56 452 454
+f 284 282 679
+f 284 679 681
+f 147 148 545
+f 147 545 544
+f 142 141 539
+f 142 539 538
+f 40 33 430
+f 40 430 437
+f 138 17 414
+f 138 414 535
+f 170 169 566
+f 170 566 568
+f 372 375 772
+f 372 772 769
+f 281 283 680
+f 281 680 678
+f 18 22 418
+f 18 418 416
+f 370 368 765
+f 370 765 767
+f 267 264 662
+f 267 662 664
+f 185 188 585
+f 185 585 582
+f 367 369 766
+f 367 766 764
+f 260 155 551
+f 260 551 657
+f 153 142 538
+f 153 538 550
+f 19 18 416
+f 19 416 415
+f 283 285 682
+f 283 682 680
+f 156 255 652
+f 156 652 553
+f 286 284 681
+f 286 681 683
+f 146 145 542
+f 146 542 543
+f 264 263 660
+f 264 660 662
+f 60 59 456
+f 60 456 457
+f 17 19 415
+f 17 415 414
+f 167 166 563
+f 167 563 564
+f 59 61 458
+f 59 458 456
+f 39 38 436
+f 39 436 435
+f 369 371 768
+f 369 768 766
+f 300 302 699
+f 300 699 697
+f 129 128 525
+f 129 525 526
+f 301 299 696
+f 301 696 698
+f 131 134 531
+f 131 531 529
+f 298 300 697
+f 298 697 695
+f 50 394 791
+f 50 791 447
+f 255 252 649
+f 255 649 652
+f 336 372 769
+f 336 769 732
+f 127 129 526
+f 127 526 524
+f 303 301 698
+f 303 698 700
+f 297 296 693
+f 297 693 694
+f 186 185 582
+f 186 582 583
+f 304 303 700
+f 304 700 701
+f 254 253 650
+f 254 650 651
+f 135 139 536
+f 135 536 532
+f 258 262 659
+f 258 659 655
+f 132 131 529
+f 132 529 528
+f 253 256 653
+f 253 653 650
+f 302 305 702
+f 302 702 699
+f 299 297 694
+f 299 694 696
+f 124 130 527
+f 124 527 522
+f 182 181 578
+f 182 578 579
+f 137 138 535
+f 137 535 534
+f 133 126 523
+f 133 523 530
+f 181 183 580
+f 181 580 578
+f 139 137 534
+f 139 534 536
+f 261 258 655
+f 261 655 658
+f 256 257 654
+f 256 654 653
+f 292 291 688
+f 292 688 689
+f 183 180 577
+f 183 577 580
+f 140 143 540
+f 140 540 537
+f 257 261 658
+f 257 658 654
+f 91 82 479
+f 91 479 488
+f 130 127 524
+f 130 524 527
+f 180 184 581
+f 180 581 577
+f 322 351 748
+f 322 748 719
+f 141 140 537
+f 141 537 539
+f 84 90 486
+f 84 486 481
+f 128 132 528
+f 128 528 525
+f 352 324 720
+f 352 720 749
+f 377 374 771
+f 377 771 774
+f 291 289 686
+f 291 686 688
+f 176 178 574
+f 176 574 573
+f 187 179 576
+f 187 576 584
+f 177 176 573
+f 177 573 575
+f 376 378 775
+f 376 775 773
+f 375 376 773
+f 375 773 772
+f 53 52 450
+f 53 450 449
+f 178 186 583
+f 178 583 574
+f 174 173 570
+f 174 570 571
+f 378 380 777
+f 378 777 775
+f 290 293 690
+f 290 690 687
+f 93 99 496
+f 93 496 490
+f 173 175 572
+f 173 572 570
+f 342 341 738
+f 342 738 739
+f 396 187 584
+f 396 584 793
+f 184 177 575
+f 184 575 581
+f 294 292 689
+f 294 689 691
+f 259 260 657
+f 259 657 656
+f 54 50 447
+f 54 447 451
+f 90 89 487
+f 90 487 486
+f 379 377 774
+f 379 774 776
+f 262 259 656
+f 262 656 659
+f 296 294 691
+f 296 691 693
+f 218 228 625
+f 218 625 615
+f 92 93 490
+f 92 490 489
+f 49 48 446
+f 49 446 445
+f 341 339 736
+f 341 736 738
+f 339 338 735
+f 339 735 736
+f 295 298 695
+f 295 695 692
+f 89 92 489
+f 89 489 487
+f 48 53 449
+f 48 449 446
+f 397 244 641
+f 397 641 794
+f 293 295 692
+f 293 692 690
+f 335 337 734
+f 335 734 733
+f 95 91 488
+f 95 488 492
+f 220 157 555
+f 220 555 617
+f 136 133 530
+f 136 530 533
+f 337 340 737
+f 337 737 734
+f 134 135 532
+f 134 532 531
+f 360 345 741
+f 360 741 757
+f 106 103 500
+f 106 500 503
+f 327 330 727
+f 327 727 725
+f 102 101 499
+f 102 499 498
+f 332 331 728
+f 332 728 729
+f 222 221 618
+f 222 618 620
+f 219 218 615
+f 219 615 616
+f 330 333 730
+f 330 730 727
+f 234 224 621
+f 234 621 631
+f 230 226 623
+f 230 623 627
+f 225 220 617
+f 225 617 622
+f 105 108 504
+f 105 504 502
+f 104 105 502
+f 104 502 501
+f 226 229 626
+f 226 626 623
+f 334 336 732
+f 334 732 731
+f 263 321 718
+f 263 718 660
+f 338 334 731
+f 338 731 735
+f 227 230 627
+f 227 627 624
+f 331 329 726
+f 331 726 728
+f 323 325 722
+f 323 722 721
+f 223 222 620
+f 223 620 619
+f 108 107 505
+f 108 505 504
+f 324 323 721
+f 324 721 720
+f 228 227 624
+f 228 624 625
+f 237 232 630
+f 237 630 634
+f 213 212 610
+f 213 610 609
+f 107 110 506
+f 107 506 505
+f 94 100 497
+f 94 497 491
+f 252 396 793
+f 252 793 649
+f 233 238 635
+f 233 635 629
+f 110 109 507
+f 110 507 506
+f 99 94 491
+f 99 491 496
+f 215 217 614
+f 215 614 612
+f 97 102 498
+f 97 498 494
+f 96 98 495
+f 96 495 493
+f 321 320 717
+f 321 717 718
+f 221 236 633
+f 221 633 618
+f 216 215 612
+f 216 612 613
+f 347 343 740
+f 347 740 744
+f 103 95 492
+f 103 492 500
+f 224 225 622
+f 224 622 621
+f 100 96 493
+f 100 493 497
+f 240 234 631
+f 240 631 637
+f 98 97 494
+f 98 494 495
+f 229 223 619
+f 229 619 626
+f 217 213 609
+f 217 609 614
+f 235 237 634
+f 235 634 632
+f 209 216 613
+f 209 613 606
+f 206 205 602
+f 206 602 603
+f 236 235 632
+f 236 632 633
+f 190 397 794
+f 190 794 587
+f 211 219 616
+f 211 616 608
+f 346 348 745
+f 346 745 743
+f 205 207 604
+f 205 604 602
+f 344 346 743
+f 344 743 742
+f 333 322 719
+f 333 719 730
+f 85 84 481
+f 85 481 482
+f 340 328 724
+f 340 724 737
+f 349 347 744
+f 349 744 746
+f 392 136 533
+f 392 533 789
+f 380 362 759
+f 380 759 777
+f 326 342 739
+f 326 739 723
+f 214 210 607
+f 214 607 611
+f 351 349 746
+f 351 746 748
+f 345 344 742
+f 345 742 741
+f 210 204 601
+f 210 601 607
+f 350 352 749
+f 350 749 747
+f 118 123 520
+f 118 520 516
+f 86 83 480
+f 86 480 483
+f 309 308 705
+f 309 705 706
+f 83 85 482
+f 83 482 480
+f 319 265 661
+f 319 661 716
+f 212 211 608
+f 212 608 610
+f 122 125 521
+f 122 521 519
+f 88 81 478
+f 88 478 485
+f 363 379 776
+f 363 776 761
+f 308 306 703
+f 308 703 705
+f 81 86 483
+f 81 483 478
+f 123 122 519
+f 123 519 520
+f 231 233 629
+f 231 629 628
+f 87 79 476
+f 87 476 484
+f 126 121 518
+f 126 518 523
+f 306 304 701
+f 306 701 703
+f 232 231 628
+f 232 628 630
+f 82 80 477
+f 82 477 479
+f 79 88 485
+f 79 485 476
+f 373 335 733
+f 373 733 770
+f 208 209 606
+f 208 606 605
+f 125 124 522
+f 125 522 521
+f 329 326 723
+f 329 723 726
+f 393 76 473
+f 393 473 790
+f 77 87 484
+f 77 484 475
+f 101 104 501
+f 101 501 499
+f 250 254 651
+f 250 651 647
+f 328 327 725
+f 328 725 724
+f 325 332 729
+f 325 729 722
+f 343 361 758
+f 343 758 740
+f 348 350 747
+f 348 747 745
+f 305 307 704
+f 305 704 702
+f 70 69 467
+f 70 467 466
+f 193 190 587
+f 193 587 590
+f 188 189 586
+f 188 586 585
+f 359 360 757
+f 359 757 756
+f 204 197 594
+f 204 594 601
+f 192 191 588
+f 192 588 589
+f 197 193 590
+f 197 590 594
+f 69 75 472
+f 69 472 467
+f 251 250 647
+f 251 647 648
+f 73 78 474
+f 73 474 470
+f 67 66 463
+f 67 463 464
+f 80 392 789
+f 80 789 477
+f 74 73 470
+f 74 470 471
+f 368 365 762
+f 368 762 765
+f 66 70 466
+f 66 466 463
+f 148 164 561
+f 148 561 545
+f 189 192 589
+f 189 589 586
+f 196 195 593
+f 196 593 592
+f 72 74 471
+f 72 471 469
+f 76 71 468
+f 76 468 473
+f 362 364 760
+f 362 760 759
+f 307 310 707
+f 307 707 704
+f 358 356 753
+f 358 753 755
+f 75 72 469
+f 75 469 472
+f 62 63 460
+f 62 460 459
+f 78 77 475
+f 78 475 474
+f 21 29 426
+f 21 426 419
+f 353 355 751
+f 353 751 750
+f 121 120 517
+f 121 517 518
+f 203 208 605
+f 203 605 599
+f 366 367 764
+f 366 764 763
+f 68 65 462
+f 68 462 465
+f 71 64 461
+f 71 461 468
+f 195 194 591
+f 195 591 593
+f 356 354 752
+f 356 752 753
+f 311 309 706
+f 311 706 708
+f 355 357 754
+f 355 754 751
+f 191 199 596
+f 191 596 588
+f 117 119 515
+f 117 515 514
+f 243 251 648
+f 243 648 639
+f 246 249 646
+f 246 646 643
+f 313 311 708
+f 313 708 710
+f 310 312 709
+f 310 709 707
+f 65 67 464
+f 65 464 462
+f 63 68 465
+f 63 465 460
+f 245 248 645
+f 245 645 642
+f 20 393 790
+f 20 790 417
+f 207 202 600
+f 207 600 604
+f 27 20 417
+f 27 417 424
+f 364 366 763
+f 364 763 760
+f 249 245 642
+f 249 642 646
+f 119 118 516
+f 119 516 515
+f 247 246 643
+f 247 643 644
+f 365 363 761
+f 365 761 762
+f 318 316 713
+f 318 713 715
+f 114 113 510
+f 114 510 511
+f 23 25 421
+f 23 421 420
+f 315 317 714
+f 315 714 712
+f 316 314 711
+f 316 711 713
+f 113 116 513
+f 113 513 510
+f 30 24 422
+f 30 422 427
+f 157 149 546
+f 157 546 555
+f 317 319 716
+f 317 716 714
+f 24 23 420
+f 24 420 422
+f 26 27 424
+f 26 424 423
+f 151 156 553
+f 151 553 548
+f 202 201 598
+f 202 598 600
+f 248 242 640
+f 248 640 645
+f 201 203 599
+f 201 599 598
+f 116 117 514
+f 116 514 513
+f 312 315 712
+f 312 712 709
+f 320 318 715
+f 320 715 717
+f 314 313 710
+f 314 710 711
+f 238 239 636
+f 238 636 635
+f 109 115 512
+f 109 512 507
+f 198 200 597
+f 198 597 595
+f 242 241 638
+f 242 638 640
+f 371 353 750
+f 371 750 768
+f 241 243 639
+f 241 639 638
+f 25 31 428
+f 25 428 421
+f 155 154 552
+f 155 552 551
+f 115 112 509
+f 115 509 512
+f 111 51 448
+f 111 448 508
+f 200 196 592
+f 200 592 597
+f 276 274 671
+f 276 671 673
+f 357 359 756
+f 357 756 754
+f 28 30 427
+f 28 427 425
+f 361 358 755
+f 361 755 758
+f 112 114 511
+f 112 511 509
+f 120 111 508
+f 120 508 517
+f 33 26 423
+f 33 423 430
+f 29 28 425
+f 29 425 426
+f 354 370 767
+f 354 767 752
+f 239 247 644
+f 239 644 636
+f 395 214 611
+f 395 611 792
+f 194 206 603
+f 194 603 591
+f 244 240 637
+f 244 637 641
+f 199 198 595
+f 199 595 596
+f 273 275 672
+f 273 672 670
+f 166 174 571
+f 166 571 563
+f 160 159 556
+f 160 556 558
+f 42 40 437
+f 42 437 439
+f 47 43 440
+f 47 440 444
+# 1588 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_l.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_l.obj
new file mode 100644
index 0000000000..e66afa7877
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_l.obj
@@ -0,0 +1,206 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object pedal_l.obj
+#
+# Vertices: 62
+# Faces: 128
+#
+####
+v 0.085626 -0.016598 -0.064180
+v 0.096574 -0.013196 -0.018622
+v 0.071940 -0.020000 -0.060383
+v 0.071940 -0.015464 -0.014826
+v 0.066466 -0.016598 -0.067975
+v -0.051227 -0.020000 -0.060383
+v -0.046300 -0.016598 -0.067975
+v -0.051227 -0.015464 -0.014826
+v 0.064824 -0.008661 -0.022419
+v 0.066466 0.020821 -0.067975
+v -0.046300 0.020821 -0.067975
+v -0.085166 -0.016598 -0.067975
+v -0.085714 -0.017732 -0.056587
+v -0.085714 -0.013196 -0.018622
+v -0.085714 -0.016598 0.019344
+v -0.051227 -0.017732 0.015546
+v 0.071940 -0.017732 0.015546
+v 0.096574 -0.016598 0.019344
+v 0.086173 -0.020000 0.053512
+v 0.071940 -0.022268 0.057308
+v -0.051227 -0.022268 0.057308
+v -0.085714 -0.020000 0.053512
+v 0.066466 -0.021134 0.068698
+v -0.046300 0.015152 0.068698
+v -0.046300 -0.021134 0.068698
+v 0.066466 0.015152 0.068698
+v -0.051227 0.018554 0.061105
+v -0.051227 0.016286 0.015547
+v -0.085714 0.016286 0.057308
+v -0.051227 0.018554 -0.011028
+v -0.085714 0.016286 -0.014825
+v -0.085714 0.019687 -0.052789
+v 0.071940 0.018554 0.061105
+v 0.085626 0.015152 0.068698
+v 0.086173 0.016286 0.057308
+v 0.071940 0.016286 0.015547
+v 0.096574 0.012884 0.019344
+v 0.071940 0.018554 -0.011028
+v 0.096574 0.016286 -0.014825
+v 0.071940 0.023089 -0.056586
+v -0.044110 0.012884 -0.018621
+v -0.051227 0.023089 -0.056586
+v -0.085166 0.020821 -0.064180
+v 0.085626 0.020821 -0.060382
+v 0.064824 0.008348 0.023140
+v 0.064824 -0.014330 0.049714
+v 0.064824 0.011750 0.053512
+v -0.044110 0.011750 0.053512
+v -0.044110 -0.014330 0.049714
+v -0.044110 0.008348 0.023140
+v -0.044110 -0.012062 0.023139
+v -0.044110 -0.013196 -0.052790
+v -0.044110 0.015152 -0.048993
+v -0.044110 -0.008661 -0.022419
+v 0.064824 -0.013196 -0.052790
+v 0.085626 -0.020000 0.064900
+v 0.064824 -0.012062 0.023139
+v -0.085714 0.014018 0.068698
+v -0.085714 -0.020000 0.064900
+v -0.085714 0.012884 0.019344
+v 0.064824 0.012884 -0.018621
+v 0.064824 0.015152 -0.048993
+# 62 vertices, 0 vertices normals
+
+f 1 2 3
+f 3 2 4
+f 5 6 7
+f 3 6 5
+f 4 8 9
+f 5 1 3
+f 7 10 5
+f 11 10 7
+f 7 12 11
+f 6 12 7
+f 13 12 6
+f 8 13 6
+f 14 13 8
+f 8 15 14
+f 16 15 8
+f 8 4 16
+f 16 4 17
+f 4 2 17
+f 17 2 18
+f 18 19 17
+f 17 19 20
+f 21 22 16
+f 16 22 15
+f 23 24 25
+f 25 20 23
+f 21 20 25
+f 26 24 23
+f 26 27 24
+f 28 29 27
+f 30 31 28
+f 30 32 31
+f 33 34 35
+f 26 34 33
+f 33 27 26
+f 33 35 36
+f 36 35 37
+f 36 37 38
+f 38 37 39
+f 38 39 40
+f 36 30 28
+f 38 30 36
+f 30 38 41
+f 42 32 30
+f 42 43 32
+f 40 39 44
+f 45 46 47
+f 47 46 48
+f 48 46 49
+f 48 49 50
+f 50 49 51
+f 52 53 54
+f 6 3 52
+f 52 3 55
+f 3 4 55
+f 55 4 9
+f 9 8 54
+f 8 52 54
+f 6 52 8
+f 5 44 1
+f 10 44 5
+f 11 12 43
+f 19 56 20
+f 20 56 23
+f 49 16 51
+f 16 17 51
+f 51 17 57
+f 17 20 57
+f 57 20 46
+f 20 21 46
+f 46 21 49
+f 21 16 49
+f 24 58 25
+f 25 59 21
+f 21 59 22
+f 25 58 59
+f 23 56 26
+f 27 58 24
+f 29 58 27
+f 60 29 28
+f 28 31 60
+f 26 56 34
+f 37 19 18
+f 35 19 37
+f 35 34 19
+f 27 33 48
+f 27 48 28
+f 28 48 50
+f 45 28 50
+f 36 28 45
+f 47 36 45
+f 33 36 47
+f 48 33 47
+f 41 38 61
+f 38 40 61
+f 61 40 62
+f 40 42 62
+f 62 42 53
+f 42 30 53
+f 53 30 41
+f 11 43 42
+f 42 40 11
+f 11 40 10
+f 40 44 10
+f 2 44 39
+f 39 37 2
+f 2 37 18
+f 1 44 2
+f 19 34 56
+f 57 46 45
+f 50 51 45
+f 45 51 57
+f 55 62 52
+f 52 62 53
+f 54 53 41
+f 54 41 9
+f 9 41 61
+f 61 62 9
+f 9 62 55
+f 43 12 32
+f 32 12 13
+f 14 32 13
+f 31 32 14
+f 31 14 60
+f 60 14 15
+f 15 22 60
+f 60 22 29
+f 22 58 29
+f 59 58 22
+# 128 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_r.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_r.obj
new file mode 100644
index 0000000000..21cc2603be
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/pedal_r.obj
@@ -0,0 +1,206 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object pedal_r.obj
+#
+# Vertices: 62
+# Faces: 128
+#
+####
+v -0.065259 -0.011327 -0.018814
+v -0.065259 -0.018131 -0.049186
+v -0.071827 -0.016997 -0.011221
+v -0.071827 -0.027202 -0.056779
+v 0.051340 -0.027202 -0.056779
+v 0.044771 -0.018131 -0.049186
+v 0.051340 -0.016997 -0.011221
+v 0.044223 -0.011327 -0.018814
+v 0.051340 -0.016997 0.015354
+v -0.071827 -0.016997 0.015354
+v 0.045866 -0.024934 -0.064372
+v -0.066901 -0.024934 -0.064372
+v 0.084732 -0.023801 -0.064372
+v 0.045866 0.013619 -0.068168
+v 0.085827 -0.023801 -0.052982
+v 0.085827 -0.014729 -0.015018
+v 0.085827 -0.014729 0.019151
+v -0.071827 -0.015863 0.060912
+v -0.065259 -0.009060 0.022947
+v 0.045866 -0.013595 0.068505
+v 0.051340 -0.015863 0.060912
+v -0.066901 -0.013595 0.068505
+v 0.045866 0.022690 0.068505
+v -0.066901 0.022690 0.068505
+v 0.085827 -0.013595 0.057115
+v 0.085827 0.021556 0.068505
+v 0.051340 0.024958 0.057115
+v -0.071827 0.024958 0.057115
+v -0.085513 0.022690 0.068505
+v -0.085513 -0.012461 0.068505
+v -0.086607 -0.013595 0.057115
+v -0.097008 0.014753 0.019151
+v -0.071827 0.017021 0.015354
+v -0.086607 0.022690 0.053319
+v 0.051340 0.017021 0.015354
+v -0.065259 0.011351 0.022947
+v -0.097008 -0.014729 0.019151
+v -0.097008 -0.014729 -0.015018
+v -0.097008 0.014753 -0.018814
+v 0.051340 0.017021 -0.015018
+v -0.071827 0.017021 -0.015018
+v -0.071827 0.015887 -0.056779
+v 0.051340 0.015887 -0.056779
+v -0.065259 0.009083 -0.049186
+v 0.044223 0.009083 -0.049186
+v 0.085827 0.014753 -0.018814
+v 0.044223 -0.009060 0.022947
+v 0.044223 0.011351 0.022947
+v 0.044223 -0.009060 0.053319
+v 0.044223 0.017021 0.053319
+v -0.065259 -0.009060 0.053319
+v -0.065259 0.017021 0.053319
+v -0.086060 0.013619 -0.060575
+v -0.066901 0.013619 -0.068168
+v 0.084732 0.013619 -0.068168
+v -0.086060 -0.023801 -0.060575
+v 0.085827 -0.012461 0.068505
+v -0.065259 0.010217 -0.022611
+v 0.044223 0.010217 -0.022611
+v 0.085827 0.013619 -0.052982
+v 0.085827 0.014753 0.019151
+v 0.085827 0.022690 0.053319
+# 62 vertices, 0 vertices normals
+
+f 1 2 3
+f 3 2 4
+f 2 5 4
+f 6 5 2
+f 6 7 5
+f 8 7 6
+f 8 1 7
+f 7 1 3
+f 3 9 7
+f 10 9 3
+f 11 12 5
+f 5 12 4
+f 13 14 11
+f 11 5 13
+f 13 5 15
+f 5 7 15
+f 15 7 16
+f 16 7 17
+f 17 7 9
+f 18 19 10
+f 18 20 21
+f 22 20 18
+f 20 22 23
+f 23 22 24
+f 17 9 25
+f 25 9 21
+f 26 20 23
+f 23 27 26
+f 23 24 27
+f 27 24 28
+f 29 28 24
+f 30 31 29
+f 32 33 34
+f 34 33 28
+f 35 36 33
+f 34 28 29
+f 29 31 34
+f 31 32 34
+f 37 32 31
+f 37 38 32
+f 32 38 39
+f 35 33 40
+f 40 33 41
+f 32 41 33
+f 39 41 32
+f 39 42 41
+f 43 44 42
+f 45 44 43
+f 40 45 43
+f 46 35 40
+f 47 48 49
+f 49 48 50
+f 49 50 51
+f 51 50 52
+f 10 47 9
+f 19 47 10
+f 53 12 54
+f 12 11 54
+f 54 11 14
+f 55 14 13
+f 51 19 18
+f 21 51 18
+f 49 51 21
+f 9 49 21
+f 47 49 9
+f 22 18 30
+f 30 18 31
+f 18 10 31
+f 31 10 37
+f 37 10 38
+f 38 10 3
+f 3 4 38
+f 38 4 56
+f 56 4 12
+f 56 12 53
+f 30 24 22
+f 29 24 30
+f 25 21 57
+f 57 21 20
+f 57 20 26
+f 33 52 28
+f 52 50 28
+f 28 50 27
+f 50 35 27
+f 48 35 50
+f 48 36 35
+f 36 52 33
+f 39 38 53
+f 53 42 39
+f 53 54 42
+f 54 14 42
+f 53 38 56
+f 42 58 41
+f 44 58 42
+f 59 45 40
+f 41 59 40
+f 58 59 41
+f 42 14 43
+f 55 43 14
+f 60 43 55
+f 60 40 43
+f 46 40 60
+f 61 35 46
+f 62 35 61
+f 27 35 62
+f 26 27 62
+f 26 25 57
+f 62 25 26
+f 62 61 25
+f 25 61 17
+f 17 61 16
+f 16 61 46
+f 60 16 46
+f 15 16 60
+f 15 60 13
+f 13 60 55
+f 45 2 44
+f 6 2 45
+f 45 8 6
+f 59 8 45
+f 59 1 8
+f 58 1 59
+f 44 1 58
+f 2 1 44
+f 19 36 47
+f 47 36 48
+f 52 36 51
+f 51 36 19
+# 128 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/saddle.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/saddle.obj
new file mode 100644
index 0000000000..a7b780868b
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/saddle.obj
@@ -0,0 +1,153 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object saddle.obj
+#
+# Vertices: 47
+# Faces: 90
+#
+####
+v 0.000274 -0.038220 0.383694
+v -0.033665 -0.026880 0.284985
+v -0.026549 -0.052961 0.387490
+v 0.000274 -0.004202 0.250817
+v 0.033666 -0.026880 0.284985
+v 0.036951 -0.006470 0.209056
+v 0.026550 -0.052961 0.387490
+v 0.036951 -0.048425 0.277393
+v 0.000274 -0.056362 0.406473
+v -0.026549 -0.075639 0.387490
+v -0.036949 -0.048425 0.277393
+v -0.036949 -0.006470 0.209056
+v 0.000274 0.021878 0.106551
+v 0.000274 -0.080175 0.398880
+v 0.026550 -0.075639 0.387490
+v -0.039139 0.017343 0.106551
+v 0.000274 0.051360 -0.037715
+v 0.039141 0.017343 0.106551
+v 0.072533 0.046824 -0.045308
+v 0.000274 0.068369 -0.197167
+v 0.090597 0.054762 -0.185778
+v -0.072531 0.046824 -0.045308
+v -0.092785 -0.007604 -0.018733
+v -0.057751 -0.012140 0.098958
+v -0.057751 -0.047291 0.091365
+v -0.068699 -0.062032 0.000250
+v -0.131104 -0.004202 -0.113645
+v -0.090596 0.054762 -0.185778
+v -0.137125 0.003736 -0.151609
+v -0.086216 0.030950 -0.197167
+v 0.142054 -0.005336 -0.151609
+v 0.131105 -0.004202 -0.113645
+v 0.136032 -0.021211 -0.159202
+v 0.057753 -0.047291 0.091365
+v 0.057753 -0.012140 0.098958
+v 0.044067 -0.034818 0.201463
+v 0.092787 -0.007604 -0.018733
+v 0.000274 0.008271 -0.109848
+v 0.115778 -0.054094 -0.094662
+v 0.000274 -0.030282 -0.007343
+v 0.068701 -0.062032 0.000250
+v -0.115776 -0.054094 -0.094662
+v -0.136031 -0.021211 -0.159202
+v 0.000274 0.046824 -0.204760
+v 0.086218 0.030950 -0.197167
+v -0.044066 -0.034818 0.201463
+v 0.000274 -0.034818 0.167295
+# 47 vertices, 0 vertices normals
+
+f 1 2 3
+f 4 2 1
+f 1 5 4
+f 6 4 5
+f 7 8 5
+f 7 5 1
+f 9 7 1
+f 9 1 3
+f 3 10 9
+f 10 3 11
+f 11 3 2
+f 2 12 11
+f 4 12 2
+f 4 13 12
+f 9 10 14
+f 15 9 14
+f 7 9 15
+f 15 8 7
+f 12 13 16
+f 13 17 16
+f 18 17 13
+f 19 17 18
+f 20 19 21
+f 17 19 20
+f 20 22 17
+f 16 17 22
+f 23 16 22
+f 24 16 23
+f 12 16 24
+f 25 24 26
+f 26 24 23
+f 22 27 23
+f 22 28 27
+f 28 22 20
+f 27 28 29
+f 28 30 29
+f 31 32 33
+f 34 35 36
+f 36 35 6
+f 36 6 8
+f 8 6 5
+f 6 13 4
+f 18 13 6
+f 6 35 18
+f 35 37 18
+f 18 37 19
+f 19 37 32
+f 19 32 21
+f 21 32 31
+f 38 39 40
+f 40 39 41
+f 38 40 42
+f 42 43 38
+f 38 44 45
+f 12 24 46
+f 11 12 46
+f 46 24 25
+f 26 23 42
+f 42 23 27
+f 44 28 20
+f 21 44 20
+f 45 44 21
+f 31 45 21
+f 33 45 31
+f 27 43 42
+f 29 43 27
+f 30 28 44
+f 29 30 43
+f 33 32 39
+f 37 39 32
+f 41 39 37
+f 35 41 37
+f 34 41 35
+f 38 45 33
+f 38 33 39
+f 41 34 40
+f 40 34 47
+f 36 47 34
+f 47 36 8
+f 8 14 47
+f 15 14 8
+f 10 11 14
+f 14 11 47
+f 47 11 46
+f 46 25 47
+f 47 25 40
+f 40 25 26
+f 42 40 26
+f 43 30 38
+f 30 44 38
+# 90 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_f.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_f.obj
new file mode 100644
index 0000000000..c1c36fef6c
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_f.obj
@@ -0,0 +1,714 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object wheel_f.obj
+#
+# Vertices: 288
+# Faces: 410
+#
+####
+v 0.056388 0.384056 -0.625587
+v -0.056378 0.172013 -0.712906
+v -0.056378 0.384056 -0.625587
+v 0.056388 0.556412 -0.477524
+v -0.056378 0.556412 -0.477524
+v 0.056388 0.676608 -0.280107
+v -0.056378 0.676608 -0.280107
+v 0.056388 0.729902 -0.059912
+v -0.056378 0.729902 -0.059912
+v -0.029008 0.650528 -0.052319
+v -0.029008 0.602903 -0.249736
+v -0.029008 0.496314 -0.424374
+v -0.029008 0.342101 -0.557250
+v -0.029008 0.153871 -0.636976
+v -0.056378 0.711759 0.167877
+v -0.029008 0.634653 0.152691
+v 0.056388 0.711759 0.167877
+v 0.056388 0.624447 0.380480
+v 0.029018 0.496314 -0.424374
+v 0.029018 0.602903 -0.249736
+v 0.029018 0.650528 -0.052319
+v 0.029018 0.634653 0.152691
+v 0.029018 0.556412 0.338718
+v 0.056388 0.475904 0.555118
+v 0.056388 -0.169297 0.710773
+v 0.056388 -0.381340 0.623454
+v 0.029018 -0.151154 0.631047
+v 0.056388 -0.728319 0.057779
+v -0.056378 -0.675025 0.277974
+v -0.056378 -0.728319 0.057779
+v 0.056388 -0.675025 0.277974
+v -0.056378 -0.554830 0.475391
+v 0.056388 -0.554830 0.475391
+v -0.056378 -0.381340 0.623454
+v -0.056378 -0.169297 0.710773
+v -0.056378 0.058621 0.729756
+v 0.056388 0.058621 0.729756
+v -0.029008 -0.494732 0.422241
+v -0.029008 -0.339385 0.555117
+v -0.029008 -0.601320 0.247603
+v -0.029008 -0.648945 0.050186
+v -0.029008 -0.633070 -0.154824
+v -0.056378 -0.710176 -0.173806
+v -0.029008 -0.554829 -0.340851
+v -0.056378 -0.622865 -0.382613
+v 0.029018 -0.339385 0.555117
+v 0.029018 -0.494732 0.422241
+v 0.029018 -0.601320 0.247603
+v 0.029018 -0.633070 -0.154824
+v -0.029008 -0.422161 -0.496507
+v -0.056378 -0.474321 -0.557250
+v -0.029008 -0.248671 -0.602808
+v -0.056378 -0.278153 -0.678738
+v 0.056388 -0.278153 -0.678738
+v 0.056388 -0.474321 -0.557250
+v 0.056388 -0.622865 -0.382613
+v 0.056388 -0.710176 -0.173806
+v 0.029018 -0.554829 -0.340851
+v 0.029018 -0.422161 -0.496507
+v 0.029018 -0.648945 0.050186
+v 0.056388 -0.055904 -0.731888
+v -0.056378 -0.055904 -0.731888
+v 0.056388 0.172013 -0.712906
+v 0.029018 0.342101 -0.557250
+v 0.029018 0.153871 -0.636976
+v -0.029008 -0.050235 -0.652162
+v -0.029008 0.423743 0.494374
+v -0.056378 0.624447 0.380480
+v -0.029008 0.556412 0.338718
+v -0.056378 0.475904 0.555118
+v -0.029008 0.251388 0.600675
+v -0.056378 0.282003 0.676605
+v -0.029008 0.052952 0.650030
+v -0.029008 -0.151154 0.631047
+v 0.029018 0.423743 0.494374
+v 0.029018 0.251388 0.600675
+v 0.029018 0.052952 0.650030
+v 0.056388 0.282003 0.676605
+v -0.002185 0.639188 -0.128248
+v -0.047072 0.032541 -0.033336
+v -0.044335 0.032541 -0.029540
+v 0.002195 0.516725 -0.397798
+v -0.041598 0.042746 0.012221
+v -0.047072 0.042746 0.012221
+v -0.002185 0.516725 -0.397798
+v -0.044335 0.045014 0.016018
+v 0.000005 0.518993 -0.394002
+v -0.047072 -0.004878 -0.044726
+v -0.002185 0.300146 -0.580029
+v 0.002195 0.300146 -0.580029
+v 0.002195 0.010997 -0.652162
+v -0.041598 0.037077 -0.025744
+v -0.047072 0.037077 -0.025744
+v -0.002185 0.010997 -0.652162
+v 0.047082 -0.013949 -0.040929
+v 0.041608 -0.013949 -0.040929
+v -0.002185 0.161808 -0.633180
+v 0.002195 0.161808 -0.633180
+v 0.000005 0.166344 -0.629384
+v 0.044345 -0.010548 -0.040929
+v -0.002185 -0.136413 -0.636976
+v 0.002195 -0.136413 -0.636976
+v 0.047082 0.030273 -0.033336
+v 0.041608 0.030273 -0.033336
+v 0.000005 -0.131877 -0.640773
+v 0.044345 0.034809 -0.033336
+v 0.002195 -0.265680 -0.595215
+v -0.041598 -0.036628 -0.021947
+v -0.047072 -0.036628 -0.025744
+v -0.002185 -0.265680 -0.595215
+v -0.044335 -0.032092 -0.025744
+v 0.000005 -0.261144 -0.595215
+v 0.000005 -0.580910 -0.295294
+v -0.002185 -0.583177 -0.291497
+v 0.041608 -0.004878 -0.044726
+v 0.044345 -0.003744 -0.048522
+v -0.041598 -0.040030 0.016018
+v 0.002195 -0.628534 -0.162417
+v 0.000005 -0.627400 -0.166213
+v -0.002185 -0.629668 -0.162417
+v -0.047072 -0.040030 0.016018
+v -0.044335 -0.038896 0.008425
+v -0.002185 -0.635338 0.137505
+v -0.047072 -0.030958 -0.029540
+v -0.044335 -0.032092 -0.033336
+v 0.000005 -0.636472 0.133708
+v -0.002185 -0.648945 -0.014354
+v 0.002195 -0.648945 -0.014354
+v 0.047082 -0.035494 0.023611
+v 0.041608 -0.035494 0.023611
+v 0.000005 -0.648945 -0.018151
+v -0.032292 -0.053637 -0.002965
+v -0.032292 0.001925 -0.056115
+v -0.019702 -0.026423 -0.002965
+v -0.032292 0.001925 0.053982
+v -0.055283 0.001925 0.053982
+v -0.055283 -0.053637 -0.002965
+v -0.055283 0.001925 -0.056115
+v -0.059663 -0.024155 -0.002965
+v -0.059663 0.001925 -0.025744
+v -0.059663 0.001925 0.023611
+v -0.055283 0.056353 -0.002965
+v 0.000005 -0.589981 0.274178
+v -0.002185 -0.587713 0.277975
+v 0.041608 -0.035494 -0.021947
+v 0.044345 -0.038896 -0.025744
+v 0.032302 -0.053637 -0.002965
+v 0.055293 -0.053637 -0.002965
+v 0.032302 0.001925 0.053982
+v 0.055293 0.001925 0.053982
+v 0.055293 0.001925 -0.056115
+v 0.059673 0.001925 -0.025744
+v 0.059673 0.001925 0.023611
+v 0.055293 0.056353 -0.002965
+v 0.020259 -0.026423 -0.002965
+v 0.000005 -0.518544 0.388072
+v -0.044335 -0.013950 0.038797
+v -0.041598 -0.011682 0.042593
+v 0.002195 -0.516276 0.391869
+v 0.002195 -0.414223 0.498170
+v 0.000005 -0.417625 0.498170
+v 0.044345 -0.004878 0.038797
+v 0.047082 -0.002610 0.042593
+v -0.002185 -0.146618 0.634844
+v 0.002195 -0.147752 0.634844
+v 0.047082 -0.038896 0.016018
+v 0.041608 -0.038896 0.016018
+v 0.000005 -0.016218 0.650030
+v -0.044335 0.021202 0.035000
+v -0.041598 0.025738 0.035000
+v -0.047072 0.025738 0.035000
+v -0.002185 -0.011682 0.650030
+v 0.002195 -0.011682 0.650030
+v 0.000005 0.580224 0.293161
+v -0.002185 0.582492 0.289364
+v 0.041608 0.045014 -0.006761
+v -0.002185 0.651662 0.000832
+v 0.002195 0.651662 0.000832
+v 0.047082 0.026872 0.035000
+v 0.041608 0.025738 0.035000
+v 0.000005 0.652795 0.004629
+v 0.047082 0.033675 0.027407
+v 0.041608 0.033675 0.027407
+v -0.002185 0.135728 0.634844
+v 0.032302 0.056353 -0.002965
+v 0.032302 0.001925 -0.056115
+v 0.020259 0.029139 -0.002965
+v 0.020259 0.001925 -0.029540
+v -0.047072 0.046148 0.000832
+v -0.002185 0.501984 0.414648
+v 0.002195 0.501984 0.414648
+v -0.041598 0.017800 0.038797
+v 0.002195 0.634653 0.145098
+v 0.000005 0.634653 0.148895
+v -0.002185 0.635787 0.145098
+v -0.047072 0.017800 0.038797
+v -0.044335 0.016666 0.042593
+v 0.029018 -0.248671 -0.602808
+v 0.029018 -0.050235 -0.652162
+v 0.000005 0.639188 -0.120655
+v -0.041598 0.031407 -0.033336
+v 0.002195 0.638054 -0.128248
+v -0.002185 0.414672 -0.504100
+v 0.002195 0.414672 -0.504100
+v 0.047082 0.043880 0.000832
+v 0.041608 0.043880 0.000832
+v 0.000005 0.418074 -0.504100
+v 0.044345 0.048416 0.004628
+v 0.000005 0.303548 -0.576233
+v -0.044335 -0.000342 -0.044726
+v -0.041598 -0.004878 -0.044726
+v 0.000005 0.015532 -0.652162
+v -0.044335 0.041613 -0.025744
+v 0.000005 -0.500401 -0.416781
+v -0.044335 0.006461 -0.048522
+v -0.041598 0.004193 -0.044726
+v 0.002195 -0.502669 -0.412984
+v -0.047072 0.004193 -0.044726
+v -0.002185 -0.503803 -0.412984
+v -0.002185 -0.392679 -0.519286
+v 0.002195 -0.392679 -0.519286
+v 0.047082 -0.041164 -0.014354
+v 0.041608 -0.041164 -0.014354
+v 0.000005 -0.388143 -0.523082
+v 0.044345 -0.036628 -0.018151
+v 0.002195 -0.583177 -0.291497
+v 0.047082 -0.006012 -0.044726
+v 0.000005 0.029139 -0.002965
+v 0.000005 0.001925 -0.029540
+v -0.019702 0.029139 -0.002965
+v -0.019702 0.001925 -0.029540
+v -0.125899 0.001925 0.023611
+v -0.125899 0.026872 -0.002965
+v -0.135205 0.001925 -0.002965
+v -0.125899 0.001925 -0.025744
+v -0.125899 -0.024155 -0.002965
+v -0.041598 -0.029824 -0.029540
+v 0.002195 -0.635338 0.137505
+v 0.044345 -0.035494 0.019814
+v -0.019702 0.001925 0.027407
+v -0.059663 0.026872 -0.002965
+v -0.032292 0.056353 -0.002965
+v 0.000005 -0.026423 -0.002965
+v 0.000005 0.001925 0.027407
+v 0.020259 0.001925 0.027407
+v 0.126457 0.026872 -0.002965
+v 0.126457 0.001925 0.023611
+v 0.135215 0.001925 -0.002965
+v 0.126457 -0.024155 -0.002965
+v 0.126457 0.001925 -0.025744
+v 0.002195 -0.587713 0.277975
+v 0.047082 -0.036628 -0.021947
+v 0.059673 -0.024155 -0.002965
+v 0.059673 0.026872 -0.002965
+v -0.047072 -0.011682 0.042593
+v -0.002185 -0.516276 0.391869
+v 0.000005 -0.290626 0.581693
+v -0.044335 -0.045699 0.004628
+v -0.041598 -0.041164 0.004628
+v 0.002195 -0.286090 0.581693
+v -0.047072 -0.041164 0.004628
+v -0.002185 -0.286090 0.585489
+v -0.002185 -0.414223 0.498170
+v 0.041608 -0.001477 0.042593
+v 0.000005 -0.151154 0.631047
+v 0.044345 -0.043432 0.016018
+v 0.000005 0.276334 0.589286
+v -0.044335 -0.023021 0.038797
+v -0.041598 -0.019619 0.035000
+v 0.002195 0.280869 0.589286
+v -0.047072 -0.019619 0.035000
+v -0.002185 0.280869 0.589286
+v 0.002195 0.582492 0.289364
+v 0.047082 0.045014 -0.006761
+v 0.044345 0.042746 -0.002965
+v 0.044345 0.026872 0.038797
+v 0.002195 0.135728 0.634844
+v 0.000005 0.131192 0.634844
+v 0.044345 0.029139 0.031204
+v -0.002185 0.405601 0.509560
+v 0.002195 0.406735 0.509560
+v 0.047082 -0.010548 0.038797
+v 0.041608 -0.010548 0.038797
+v 0.000005 0.402199 0.513356
+v 0.044345 -0.013950 0.042593
+v 0.000005 0.498582 0.414648
+v -0.044335 0.042746 0.004628
+v -0.041598 0.045014 0.000832
+# 288 vertices, 0 vertices normals
+
+f 1 2 3
+f 1 3 4
+f 4 3 5
+f 4 5 6
+f 6 5 7
+f 6 7 8
+f 8 7 9
+f 9 7 10
+f 10 7 11
+f 7 5 11
+f 11 5 12
+f 5 3 12
+f 12 3 13
+f 3 2 13
+f 13 2 14
+f 9 15 8
+f 15 9 16
+f 16 9 10
+f 17 15 18
+f 8 15 17
+f 4 6 19
+f 19 6 20
+f 6 8 20
+f 20 8 21
+f 8 17 21
+f 21 17 22
+f 17 18 22
+f 22 18 23
+f 18 24 23
+f 25 26 27
+f 28 29 30
+f 31 29 28
+f 31 32 29
+f 33 32 31
+f 33 34 32
+f 26 34 33
+f 26 35 34
+f 25 35 26
+f 25 36 35
+f 37 36 25
+f 38 34 39
+f 32 34 38
+f 40 32 38
+f 29 32 40
+f 41 29 40
+f 30 29 41
+f 42 30 41
+f 43 30 42
+f 44 43 42
+f 45 43 44
+f 39 46 38
+f 38 46 47
+f 38 47 40
+f 40 47 48
+f 40 48 41
+f 42 49 44
+f 50 45 44
+f 51 45 50
+f 52 51 50
+f 53 51 52
+f 54 51 53
+f 55 51 54
+f 55 45 51
+f 56 45 55
+f 56 43 45
+f 57 43 56
+f 57 30 43
+f 28 30 57
+f 56 55 58
+f 58 55 59
+f 55 54 59
+f 28 57 60
+f 61 62 63
+f 13 64 12
+f 13 65 64
+f 14 65 13
+f 14 62 66
+f 2 62 14
+f 63 62 2
+f 63 2 1
+f 67 68 69
+f 70 68 67
+f 71 70 67
+f 72 70 71
+f 73 72 71
+f 36 72 73
+f 74 36 73
+f 35 36 74
+f 39 35 74
+f 34 35 39
+f 67 75 71
+f 71 75 76
+f 71 76 73
+f 73 76 77
+f 73 77 74
+f 37 72 36
+f 78 72 37
+f 78 70 72
+f 24 70 78
+f 24 68 70
+f 18 68 24
+f 18 15 68
+f 68 15 69
+f 69 15 16
+f 79 80 81
+f 82 83 84
+f 84 85 82
+f 85 84 86
+f 86 87 85
+f 88 89 90
+f 91 92 93
+f 93 94 91
+f 95 96 97
+f 98 99 100
+f 101 102 103
+f 103 104 101
+f 105 101 104
+f 104 106 105
+f 107 108 109
+f 109 110 107
+f 110 109 111
+f 111 112 110
+f 113 114 115
+f 115 116 113
+f 117 118 119
+f 120 121 122
+f 123 124 125
+f 125 126 123
+f 127 128 129
+f 129 130 127
+f 131 127 130
+f 132 133 134
+f 135 136 132
+f 132 136 137
+f 132 137 133
+f 133 137 138
+f 138 139 140
+f 137 139 138
+f 137 141 139
+f 136 141 137
+f 135 142 136
+f 143 144 145
+f 145 146 143
+f 147 148 149
+f 149 148 150
+f 147 151 148
+f 151 152 148
+f 150 153 154
+f 147 149 155
+f 156 157 158
+f 158 159 156
+f 160 161 162
+f 162 163 160
+f 164 165 166
+f 166 167 164
+f 168 169 170
+f 171 172 173
+f 174 175 176
+f 177 178 179
+f 179 180 177
+f 181 177 180
+f 182 183 184
+f 185 186 187
+f 187 186 188
+f 189 190 191
+f 192 193 194
+f 195 196 197
+f 10 22 16
+f 21 22 10
+f 10 20 21
+f 11 20 10
+f 11 19 20
+f 12 19 11
+f 12 64 19
+f 65 1 64
+f 1 4 64
+f 64 4 19
+f 23 24 75
+f 24 78 75
+f 75 78 76
+f 78 37 76
+f 76 37 77
+f 37 25 77
+f 77 25 27
+f 39 27 46
+f 41 48 60
+f 41 60 42
+f 42 60 49
+f 44 49 58
+f 44 58 50
+f 50 58 59
+f 50 59 52
+f 52 59 198
+f 52 198 66
+f 66 198 199
+f 66 53 52
+f 62 53 66
+f 61 53 62
+f 54 53 61
+f 49 56 58
+f 59 54 198
+f 54 61 198
+f 198 61 199
+f 27 26 46
+f 26 33 46
+f 46 33 47
+f 33 31 47
+f 47 31 48
+f 31 28 48
+f 48 28 60
+f 60 57 49
+f 57 56 49
+f 61 63 199
+f 199 63 65
+f 14 199 65
+f 66 199 14
+f 63 1 65
+f 69 22 23
+f 69 23 67
+f 67 23 75
+f 74 77 27
+f 74 27 39
+f 16 22 69
+f 200 81 201
+f 201 202 200
+f 202 201 80
+f 80 79 202
+f 81 200 79
+f 87 86 83
+f 83 82 87
+f 203 204 205
+f 205 206 203
+f 207 203 206
+f 206 208 207
+f 204 207 208
+f 208 205 204
+f 209 210 211
+f 211 90 209
+f 90 211 88
+f 89 88 210
+f 210 209 89
+f 212 213 92
+f 92 91 212
+f 94 93 213
+f 213 212 94
+f 97 98 95
+f 99 97 96
+f 96 100 99
+f 100 95 98
+f 102 105 106
+f 106 103 102
+f 112 111 108
+f 108 107 112
+f 214 215 216
+f 216 217 214
+f 217 216 218
+f 218 219 217
+f 219 218 215
+f 215 214 219
+f 220 221 222
+f 222 223 220
+f 224 220 223
+f 223 225 224
+f 221 224 225
+f 225 222 221
+f 114 226 227
+f 227 115 114
+f 228 229 230
+f 230 229 231
+f 232 233 234
+f 233 235 234
+f 235 236 234
+f 236 232 234
+f 226 113 116
+f 116 227 226
+f 119 122 117
+f 118 117 121
+f 121 120 118
+f 122 119 120
+f 126 125 237
+f 237 238 126
+f 238 237 124
+f 124 123 238
+f 130 239 131
+f 134 133 231
+f 240 132 134
+f 135 132 240
+f 136 241 141
+f 142 241 136
+f 242 142 135
+f 240 242 135
+f 230 242 240
+f 241 140 233
+f 233 140 235
+f 228 187 229
+f 229 187 188
+f 229 188 243
+f 243 188 155
+f 243 155 244
+f 244 155 245
+f 244 245 228
+f 228 245 187
+f 246 247 248
+f 247 249 248
+f 249 250 248
+f 250 246 248
+f 128 131 239
+f 239 129 128
+f 144 251 252
+f 252 145 144
+f 186 151 147
+f 148 152 253
+f 148 253 150
+f 150 253 153
+f 154 153 254
+f 185 150 154
+f 149 150 185
+f 187 149 185
+f 245 149 187
+f 155 149 245
+f 188 147 155
+f 186 147 188
+f 152 254 250
+f 250 254 246
+f 254 153 246
+f 246 153 247
+f 153 253 247
+f 247 253 249
+f 253 152 249
+f 249 152 250
+f 251 143 146
+f 146 252 251
+f 159 158 255
+f 255 256 159
+f 256 255 157
+f 157 156 256
+f 257 258 259
+f 259 260 257
+f 260 259 261
+f 261 262 260
+f 262 261 258
+f 258 257 262
+f 263 160 163
+f 163 264 263
+f 161 263 264
+f 264 162 161
+f 265 164 167
+f 167 266 265
+f 165 265 266
+f 266 166 165
+f 170 173 168
+f 173 170 171
+f 172 171 169
+f 169 168 172
+f 267 268 269
+f 269 270 267
+f 270 269 271
+f 271 272 270
+f 272 271 268
+f 268 267 272
+f 175 273 274
+f 274 176 175
+f 176 275 174
+f 273 174 275
+f 275 274 273
+f 180 276 181
+f 178 181 276
+f 276 179 178
+f 184 277 182
+f 278 184 183
+f 183 279 278
+f 277 278 279
+f 279 182 277
+f 280 281 282
+f 282 283 280
+f 284 280 283
+f 283 285 284
+f 151 254 152
+f 154 254 151
+f 186 154 151
+f 185 154 186
+f 281 284 285
+f 285 282 281
+f 286 287 288
+f 288 191 286
+f 191 288 189
+f 190 189 287
+f 287 286 190
+f 194 197 192
+f 193 192 196
+f 196 195 193
+f 197 194 195
+f 142 140 241
+f 138 140 142
+f 242 138 142
+f 133 138 242
+f 133 242 231
+f 231 242 230
+f 232 241 233
+f 141 241 232
+f 236 141 232
+f 139 141 236
+f 235 139 236
+f 140 139 235
+f 240 228 230
+f 244 228 240
+f 134 244 240
+f 243 244 134
+f 231 243 134
+f 229 243 231
+# 410 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_r.obj b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_r.obj
new file mode 100644
index 0000000000..33ab8134c8
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleCycling/geometry/wheel_r.obj
@@ -0,0 +1,822 @@
+####
+#
+# OBJ File Generated by Meshlab
+#
+####
+# Object wheel_r.obj
+#
+# Vertices: 344
+# Faces: 462
+#
+####
+v 0.056655 0.383112 -0.624623
+v -0.056111 0.171069 -0.711943
+v -0.056111 0.383112 -0.624623
+v 0.056655 0.555468 -0.476561
+v -0.056111 0.555468 -0.476561
+v 0.056655 0.675663 -0.279144
+v -0.056111 0.675663 -0.279144
+v 0.056655 0.728957 -0.058948
+v -0.056111 0.728957 -0.058948
+v -0.028741 0.649583 -0.051355
+v -0.028741 0.601958 -0.248772
+v -0.028741 0.495370 -0.423410
+v -0.028741 0.341157 -0.556287
+v -0.028741 0.152926 -0.632217
+v -0.056111 0.710815 0.172637
+v -0.028741 0.633708 0.153654
+v 0.029285 0.601958 -0.248772
+v 0.056655 0.710815 0.172637
+v 0.056655 0.623503 0.381443
+v 0.029285 0.495370 -0.423410
+v 0.029285 0.649583 -0.051355
+v 0.029285 0.633708 0.153654
+v 0.029285 0.555467 0.339682
+v 0.056655 0.474959 0.556081
+v 0.029285 0.422799 0.495337
+v 0.056655 0.281059 0.677568
+v 0.056655 0.057677 0.730719
+v 0.056655 -0.170241 0.711737
+v 0.029285 0.052007 0.650993
+v 0.029285 -0.152099 0.635807
+v 0.056655 -0.382284 0.624418
+v 0.056655 -0.729264 0.058742
+v -0.056111 -0.675970 0.278938
+v -0.056111 -0.729264 0.058742
+v 0.056655 -0.675970 0.278938
+v -0.056111 -0.555774 0.476355
+v 0.056655 -0.555774 0.476355
+v -0.056111 -0.382284 0.624418
+v -0.056111 -0.170241 0.711737
+v -0.056111 0.057677 0.730719
+v -0.028741 -0.495676 0.423204
+v -0.028741 -0.340329 0.556081
+v -0.028741 -0.602265 0.248566
+v -0.028741 -0.649889 0.051149
+v -0.028741 -0.634014 -0.153860
+v -0.056111 -0.711121 -0.169046
+v -0.028741 -0.555774 -0.339888
+v -0.056111 -0.623809 -0.381649
+v 0.029285 -0.495676 0.423204
+v 0.029285 -0.649889 0.051149
+v 0.029285 -0.555774 -0.339888
+v -0.028741 -0.423105 -0.495543
+v 0.029285 -0.423105 -0.495543
+v -0.028741 -0.249616 -0.601845
+v 0.029285 -0.249616 -0.601845
+v -0.028741 -0.051180 -0.651199
+v -0.056111 -0.475266 -0.556287
+v -0.056111 -0.279097 -0.677774
+v 0.056655 -0.279097 -0.677774
+v 0.056655 -0.056849 -0.730925
+v 0.056655 -0.475266 -0.556287
+v 0.056655 -0.623809 -0.381649
+v 0.056655 -0.711121 -0.169046
+v 0.029285 -0.340329 0.556081
+v 0.029285 -0.602265 0.248566
+v 0.029285 -0.634014 -0.153860
+v 0.029285 -0.051180 -0.651199
+v 0.056655 0.171069 -0.711943
+v 0.029285 0.152926 -0.632217
+v 0.029285 0.341157 -0.556287
+v -0.056111 -0.056849 -0.730925
+v -0.028741 0.422799 0.495337
+v -0.056111 0.623503 0.381443
+v -0.028741 0.555467 0.339682
+v -0.056111 0.474959 0.556081
+v -0.028741 0.250443 0.601639
+v -0.056111 0.281059 0.677568
+v -0.028741 0.052007 0.650993
+v -0.028741 -0.152099 0.635807
+v 0.029285 0.250443 0.601639
+v -0.062680 -0.029635 0.127079
+v -0.062680 0.076953 -0.100710
+v -0.062680 0.048605 -0.115895
+v -0.062680 0.017989 -0.123489
+v -0.062680 -0.013760 -0.123489
+v -0.062680 -0.044376 -0.115895
+v -0.062680 -0.072724 -0.100710
+v -0.062680 -0.095403 -0.077931
+v -0.062680 -0.112411 -0.051356
+v -0.062680 -0.122617 -0.020984
+v -0.062680 -0.124885 0.009388
+v -0.062680 -0.059117 0.115689
+v -0.062680 -0.085197 0.096707
+v -0.062680 -0.105608 0.070132
+v -0.062680 -0.119215 0.043557
+v -0.062680 0.002114 0.130875
+v -0.062680 0.033864 0.127079
+v -0.062680 0.063346 0.115690
+v -0.062680 0.089426 0.096707
+v -0.062680 0.109837 0.070132
+v -0.062680 0.123444 0.043557
+v -0.062680 0.129114 0.009388
+v -0.062680 0.126846 -0.020984
+v -0.062680 0.116641 -0.051355
+v -0.062680 0.099632 -0.077931
+v -0.057206 0.048605 -0.115895
+v -0.057206 0.076953 -0.100710
+v -0.057206 -0.029635 0.127079
+v -0.057206 0.017989 -0.123489
+v -0.057206 -0.013760 -0.123489
+v -0.057206 -0.044376 -0.115895
+v -0.057206 -0.072724 -0.100710
+v -0.057206 -0.095403 -0.077931
+v -0.057206 -0.112411 -0.051356
+v -0.057206 -0.122617 -0.020984
+v -0.057206 -0.124885 0.009388
+v -0.057206 -0.059117 0.115689
+v -0.057206 -0.085197 0.096707
+v -0.057206 -0.105608 0.070132
+v -0.057206 -0.119215 0.043557
+v -0.057206 0.033864 0.127079
+v -0.057206 0.002114 0.130875
+v -0.057206 0.063346 0.115690
+v -0.057206 0.089426 0.096707
+v -0.057206 0.109837 0.070132
+v -0.057206 0.123444 0.043557
+v -0.057206 0.129114 0.009388
+v -0.057206 0.126846 -0.020984
+v -0.057206 0.116641 -0.051355
+v -0.057206 0.099632 -0.077931
+v 0.000272 0.638244 -0.119692
+v -0.044068 0.031597 -0.028577
+v -0.041331 0.030463 -0.032373
+v -0.046805 0.031597 -0.032373
+v -0.001918 0.638244 -0.127285
+v 0.002462 0.637110 -0.127285
+v 0.002462 0.515780 -0.396835
+v -0.041331 0.041802 0.013185
+v -0.046805 0.041802 0.013185
+v -0.001918 0.515780 -0.396835
+v 0.002462 0.592887 -0.267755
+v 0.000272 0.595155 -0.260162
+v 0.044612 0.024793 -0.032373
+v 0.047349 0.023659 -0.039966
+v -0.019435 0.000981 0.028371
+v -0.032025 -0.054581 0.001795
+v -0.019435 -0.027367 0.001795
+v -0.032025 0.000981 0.054946
+v -0.055016 0.000981 0.054946
+v -0.055016 -0.054581 0.001795
+v -0.032025 0.055409 0.001795
+v -0.019435 0.028195 0.001795
+v 0.000272 0.000981 -0.028577
+v 0.020526 0.028195 0.001795
+v 0.020526 0.000981 -0.028577
+v 0.000272 0.028195 0.001795
+v 0.000272 0.302603 -0.575269
+v -0.044068 -0.001287 -0.039966
+v -0.041331 -0.005823 -0.043762
+v 0.002462 0.299202 -0.579066
+v -0.046805 0.036132 -0.024780
+v -0.001918 0.010052 -0.651199
+v 0.002462 0.010052 -0.651199
+v 0.047349 0.029329 -0.032373
+v 0.041875 0.029329 -0.032373
+v -0.001918 -0.137357 -0.636013
+v 0.002462 -0.266624 -0.594252
+v -0.041331 -0.037573 -0.020984
+v -0.046805 -0.037573 -0.020984
+v -0.001918 -0.266624 -0.594252
+v -0.044068 -0.033037 -0.024780
+v 0.002462 -0.503614 -0.412021
+v -0.041331 0.003248 -0.043762
+v -0.046805 0.003248 -0.043762
+v -0.001918 -0.504748 -0.412021
+v -0.044068 0.005516 -0.047559
+v 0.047349 -0.042108 -0.013391
+v 0.041875 -0.042108 -0.013391
+v -0.001918 -0.393623 -0.518322
+v 0.002462 -0.393623 -0.518322
+v 0.000272 -0.389088 -0.522119
+v 0.044612 -0.037573 -0.017187
+v 0.047349 -0.006957 -0.043762
+v 0.041875 -0.005823 -0.043762
+v -0.001918 -0.584122 -0.286737
+v 0.000272 -0.581854 -0.294330
+v 0.044612 -0.004689 -0.047559
+v -0.001918 -0.630613 -0.161454
+v -0.046805 -0.040974 0.016981
+v -0.044068 -0.039840 0.013185
+v -0.046805 -0.031903 -0.028577
+v -0.001918 -0.636282 0.138468
+v 0.002462 -0.636282 0.138468
+v -0.001918 -0.517221 0.396629
+v -0.046805 -0.012626 0.043557
+v -0.044068 -0.014894 0.039760
+v 0.000272 -0.519489 0.389036
+v 0.002462 -0.287035 0.586453
+v -0.041331 -0.042108 0.005592
+v -0.046805 -0.042108 0.005592
+v -0.001918 -0.287035 0.586453
+v 0.000272 -0.418570 0.499134
+v -0.001918 -0.415168 0.499134
+v 0.041875 -0.002421 0.043557
+v 0.002462 -0.148697 0.635807
+v 0.000272 -0.152099 0.635807
+v 0.044612 -0.044376 0.016981
+v 0.000272 -0.017162 0.650993
+v -0.044068 0.020257 0.035964
+v -0.041331 0.024793 0.035964
+v -0.046805 0.024793 0.035964
+v -0.001918 -0.012626 0.650993
+v 0.002462 -0.012626 0.650993
+v -0.046805 -0.020564 0.039760
+v -0.001918 0.279925 0.590249
+v 0.002462 0.279925 0.590249
+v -0.044068 -0.023966 0.039760
+v -0.001918 0.581548 0.290328
+v 0.002462 0.581548 0.290328
+v 0.047349 0.044070 -0.005798
+v 0.041875 0.044070 -0.005798
+v 0.000272 0.579280 0.294124
+v 0.044612 0.041802 -0.002001
+v -0.001918 0.650717 0.001795
+v 0.002462 0.650717 0.001795
+v 0.047349 0.025927 0.035964
+v 0.041875 0.024793 0.035964
+v 0.000272 0.651851 0.005592
+v 0.047349 0.032730 0.032167
+v 0.041875 0.032731 0.028371
+v -0.001918 0.134783 0.635807
+v 0.002462 0.134783 0.635807
+v 0.000272 0.130247 0.635807
+v 0.044612 0.028195 0.032167
+v 0.000272 0.401254 0.514320
+v -0.001918 0.404656 0.510523
+v 0.041875 -0.011493 0.039760
+v 0.044612 -0.014894 0.043557
+v 0.047349 -0.011493 0.039760
+v 0.002462 0.405790 0.510523
+v -0.001918 0.501039 0.415612
+v -0.046805 0.045204 0.001795
+v -0.044068 0.041802 0.005592
+v 0.000272 0.497638 0.419408
+v 0.002462 0.633708 0.146061
+v -0.041331 0.016855 0.039760
+v -0.046805 0.016855 0.039760
+v -0.001918 0.634842 0.146061
+v 0.126724 0.025927 0.001795
+v 0.126724 0.000981 0.024574
+v 0.135482 0.000981 0.001795
+v 0.126724 -0.025099 0.001795
+v 0.126724 0.000981 -0.024780
+v 0.032569 -0.054581 0.001795
+v 0.055560 -0.054581 0.001795
+v 0.032569 0.000981 0.054946
+v 0.055560 0.000981 0.054946
+v 0.020526 -0.027367 0.001795
+v -0.125632 -0.025099 0.001795
+v -0.059396 0.000981 0.024574
+v -0.125632 0.000981 0.024574
+v -0.059396 -0.025099 0.001795
+v 0.000272 0.518048 -0.393039
+v -0.044068 0.044070 0.016981
+v -0.001918 0.592887 -0.263958
+v 0.041875 0.022525 -0.036170
+v 0.047349 -0.039840 0.016981
+v 0.041875 -0.039840 0.016981
+v -0.001918 -0.147563 0.635807
+v -0.019435 0.000981 -0.028577
+v 0.000272 -0.027367 0.001795
+v 0.000272 0.000981 0.028371
+v 0.020526 0.000981 0.028371
+v -0.125632 0.025927 0.001795
+v -0.134938 0.000981 0.001795
+v -0.125632 0.000981 -0.024780
+v -0.001918 0.413728 -0.503136
+v 0.002462 0.413728 -0.503136
+v 0.047349 0.042936 0.001795
+v 0.041875 0.042936 0.001795
+v 0.000272 0.417129 -0.499340
+v 0.044612 0.047472 0.005592
+v -0.032025 0.000981 -0.055152
+v -0.055016 0.000981 -0.055152
+v -0.059396 0.000981 -0.024780
+v -0.059396 0.025927 0.001795
+v -0.055016 0.055409 0.001795
+v -0.046805 -0.005823 -0.043762
+v -0.001918 0.299202 -0.579066
+v 0.000272 0.014588 -0.651199
+v -0.044068 0.040668 -0.024780
+v -0.041331 0.036132 -0.024780
+v -0.001918 0.160863 -0.628420
+v 0.002462 0.160863 -0.632217
+v 0.047349 -0.014894 -0.039966
+v 0.041875 -0.014894 -0.039966
+v 0.000272 0.165399 -0.628420
+v 0.044612 -0.011492 -0.039966
+v 0.002462 -0.137357 -0.636013
+v 0.000272 -0.132822 -0.639810
+v 0.044612 0.033864 -0.032373
+v 0.000272 -0.262089 -0.594252
+v 0.000272 -0.501346 -0.415817
+v 0.002462 -0.584122 -0.286737
+v 0.000272 -0.628345 -0.165250
+v -0.041331 -0.040974 0.016981
+v 0.002462 -0.629479 -0.161454
+v 0.000272 -0.637416 0.134672
+v -0.044068 -0.033037 -0.032373
+v -0.041331 -0.030769 -0.028577
+v -0.001918 -0.649889 -0.013391
+v 0.002462 -0.649889 -0.013391
+v 0.047349 -0.036439 0.024574
+v 0.041875 -0.036439 0.024574
+v 0.000272 -0.649889 -0.017187
+v 0.044612 -0.036439 0.020778
+v -0.001918 -0.588658 0.278938
+v 0.002462 -0.588658 0.278938
+v 0.047349 -0.037573 -0.020984
+v 0.041875 -0.036439 -0.020984
+v 0.000272 -0.590926 0.275141
+v 0.044612 -0.039840 -0.024780
+v -0.041331 -0.012626 0.043557
+v 0.002462 -0.517221 0.392832
+v 0.000272 -0.291571 0.582656
+v -0.044068 -0.046644 0.005592
+v 0.002462 -0.415168 0.502930
+v 0.047349 -0.003555 0.043557
+v 0.044612 -0.005823 0.039760
+v 0.000272 0.275389 0.590249
+v -0.041331 -0.020564 0.035964
+v 0.044612 0.025927 0.039760
+v -0.041331 0.044070 0.001795
+v 0.002462 0.501039 0.415612
+v 0.000272 0.633708 0.153654
+v -0.044068 0.015722 0.043557
+v 0.032569 0.000981 -0.055152
+v 0.055560 0.000981 -0.055152
+v 0.059940 0.000981 -0.024780
+v 0.059940 -0.025099 0.001795
+v 0.059940 0.000981 0.024574
+v 0.055560 0.055409 0.001795
+v 0.059940 0.025927 0.001795
+v 0.032569 0.055409 0.001795
+# 344 vertices, 0 vertices normals
+
+f 1 2 3
+f 1 3 4
+f 4 3 5
+f 4 5 6
+f 6 5 7
+f 6 7 8
+f 8 7 9
+f 9 7 10
+f 10 7 11
+f 7 5 11
+f 11 5 12
+f 5 3 12
+f 12 3 13
+f 3 2 13
+f 13 2 14
+f 9 15 8
+f 15 9 16
+f 16 9 10
+f 11 17 10
+f 18 15 19
+f 8 15 18
+f 4 6 20
+f 8 18 21
+f 21 18 22
+f 18 19 22
+f 22 19 23
+f 19 24 23
+f 23 24 25
+f 24 26 25
+f 27 28 29
+f 29 28 30
+f 28 31 30
+f 32 33 34
+f 35 33 32
+f 35 36 33
+f 37 36 35
+f 37 38 36
+f 31 38 37
+f 31 39 38
+f 28 39 31
+f 28 40 39
+f 27 40 28
+f 41 38 42
+f 36 38 41
+f 43 36 41
+f 33 36 43
+f 44 33 43
+f 34 33 44
+f 45 34 44
+f 46 34 45
+f 47 46 45
+f 48 46 47
+f 41 49 43
+f 44 50 45
+f 47 51 52
+f 52 51 53
+f 52 53 54
+f 54 53 55
+f 54 55 56
+f 52 48 47
+f 57 48 52
+f 54 57 52
+f 58 57 54
+f 56 58 54
+f 59 58 60
+f 59 57 58
+f 61 57 59
+f 61 48 57
+f 62 48 61
+f 62 46 48
+f 63 46 62
+f 63 34 46
+f 32 34 63
+f 30 31 64
+f 31 37 64
+f 35 32 65
+f 63 62 66
+f 67 68 69
+f 13 70 12
+f 2 71 14
+f 68 71 2
+f 68 2 1
+f 68 1 69
+f 72 73 74
+f 75 73 72
+f 76 75 72
+f 77 75 76
+f 78 77 76
+f 40 77 78
+f 79 40 78
+f 39 40 79
+f 42 39 79
+f 38 39 42
+f 76 80 78
+f 27 77 40
+f 26 77 27
+f 26 75 77
+f 24 75 26
+f 24 73 75
+f 19 73 24
+f 19 15 73
+f 73 15 74
+f 74 15 16
+f 81 82 83
+f 81 83 84
+f 81 84 85
+f 81 85 86
+f 81 86 87
+f 81 87 88
+f 81 88 89
+f 81 89 90
+f 81 90 91
+f 92 81 91
+f 93 92 91
+f 94 93 91
+f 95 94 91
+f 81 96 97
+f 81 97 98
+f 81 98 99
+f 81 99 100
+f 81 100 101
+f 81 101 102
+f 81 102 103
+f 81 103 104
+f 81 104 105
+f 81 105 82
+f 106 107 108
+f 109 106 108
+f 110 109 108
+f 111 110 108
+f 112 111 108
+f 113 112 108
+f 114 113 108
+f 115 114 108
+f 116 115 108
+f 116 108 117
+f 116 117 118
+f 116 118 119
+f 120 116 119
+f 121 122 108
+f 123 121 108
+f 124 123 108
+f 125 124 108
+f 126 125 108
+f 127 126 108
+f 128 127 108
+f 129 128 108
+f 130 129 108
+f 107 130 108
+f 131 132 133
+f 134 135 136
+f 137 138 139
+f 139 140 137
+f 141 142 143
+f 143 144 141
+f 145 146 147
+f 148 146 145
+f 148 149 146
+f 146 149 150
+f 145 151 148
+f 152 151 145
+f 153 154 155
+f 156 154 153
+f 157 158 159
+f 159 160 157
+f 161 162 163
+f 164 165 166
+f 167 168 169
+f 169 170 167
+f 170 169 171
+f 172 173 174
+f 174 175 172
+f 175 174 176
+f 177 178 179
+f 180 181 182
+f 183 184 185
+f 186 185 184
+f 184 187 186
+f 188 189 190
+f 191 192 193
+f 194 195 196
+f 196 197 194
+f 198 199 200
+f 200 201 198
+f 202 203 204
+f 205 206 207
+f 208 209 210
+f 211 212 213
+f 214 215 216
+f 215 214 217
+f 218 219 220
+f 220 221 218
+f 222 218 221
+f 221 223 222
+f 224 225 226
+f 226 227 224
+f 228 224 227
+f 229 230 231
+f 232 233 234
+f 235 236 237
+f 238 239 240
+f 241 242 243
+f 243 244 241
+f 245 246 247
+f 247 248 245
+f 249 250 251
+f 250 252 251
+f 252 253 251
+f 253 249 251
+f 254 255 256
+f 256 255 257
+f 254 256 258
+f 259 260 261
+f 262 260 259
+f 10 22 16
+f 21 22 10
+f 10 17 21
+f 11 20 17
+f 12 20 11
+f 12 70 20
+f 69 1 70
+f 1 4 70
+f 70 4 20
+f 20 6 17
+f 6 8 17
+f 17 8 21
+f 25 26 80
+f 26 27 80
+f 80 27 29
+f 42 30 64
+f 42 64 41
+f 41 64 49
+f 43 49 65
+f 43 65 44
+f 44 65 50
+f 45 50 66
+f 45 66 47
+f 47 66 51
+f 56 55 67
+f 71 58 56
+f 60 58 71
+f 66 62 51
+f 62 61 51
+f 51 61 53
+f 61 59 53
+f 53 59 55
+f 59 60 55
+f 55 60 67
+f 64 37 49
+f 37 35 49
+f 49 35 65
+f 65 32 50
+f 32 63 50
+f 50 63 66
+f 60 71 68
+f 60 68 67
+f 13 69 70
+f 14 69 13
+f 14 67 69
+f 56 67 14
+f 14 71 56
+f 74 22 23
+f 74 23 72
+f 72 23 25
+f 72 25 76
+f 76 25 80
+f 78 80 29
+f 78 29 79
+f 79 29 30
+f 79 30 42
+f 16 22 74
+f 133 136 131
+f 136 133 134
+f 135 134 132
+f 132 131 135
+f 263 264 138
+f 138 137 263
+f 140 139 264
+f 264 263 140
+f 265 141 144
+f 144 266 265
+f 142 265 266
+f 266 143 142
+f 267 268 269
+f 206 269 268
+f 268 207 206
+f 269 205 267
+f 156 153 152
+f 152 153 270
+f 153 155 271
+f 271 155 258
+f 271 258 272
+f 272 258 273
+f 272 273 156
+f 156 273 154
+f 261 274 275
+f 274 276 275
+f 276 259 275
+f 259 261 275
+f 277 278 279
+f 279 280 277
+f 281 277 280
+f 280 282 281
+f 146 283 147
+f 147 283 270
+f 146 150 283
+f 283 150 284
+f 284 262 285
+f 150 262 284
+f 150 260 262
+f 149 260 150
+f 149 286 260
+f 287 286 149
+f 148 287 149
+f 151 287 148
+f 286 285 274
+f 274 285 276
+f 153 271 270
+f 270 271 147
+f 271 272 147
+f 147 272 145
+f 272 156 145
+f 145 156 152
+f 278 281 282
+f 282 279 278
+f 160 159 288
+f 288 289 160
+f 289 288 158
+f 158 157 289
+f 290 291 292
+f 292 163 290
+f 163 292 161
+f 162 161 291
+f 291 290 162
+f 293 294 295
+f 295 296 293
+f 297 293 296
+f 296 298 297
+f 294 297 298
+f 298 295 294
+f 166 299 164
+f 300 166 165
+f 165 301 300
+f 299 300 301
+f 301 164 299
+f 302 171 168
+f 168 167 302
+f 171 302 170
+f 303 176 173
+f 173 172 303
+f 176 303 175
+f 179 180 177
+f 181 179 178
+f 178 182 181
+f 182 177 180
+f 185 304 183
+f 304 186 187
+f 187 183 304
+f 305 190 306
+f 306 307 305
+f 307 306 189
+f 189 188 307
+f 190 305 188
+f 308 309 310
+f 310 193 308
+f 193 310 191
+f 192 191 309
+f 309 308 192
+f 311 312 313
+f 313 314 311
+f 315 311 314
+f 314 316 315
+f 312 315 316
+f 316 313 312
+f 317 318 319
+f 319 320 317
+f 321 317 320
+f 320 322 321
+f 318 321 322
+f 322 319 318
+f 197 196 323
+f 323 324 197
+f 324 323 195
+f 195 194 324
+f 325 326 199
+f 199 198 325
+f 201 200 326
+f 326 325 201
+f 203 327 328
+f 328 204 203
+f 204 329 202
+f 327 202 329
+f 329 328 327
+f 207 267 205
+f 210 213 208
+f 213 210 211
+f 212 211 209
+f 209 208 212
+f 330 217 331
+f 331 216 330
+f 216 331 214
+f 217 330 215
+f 219 222 223
+f 223 220 219
+f 227 332 228
+f 225 228 332
+f 332 226 225
+f 231 232 229
+f 233 231 230
+f 230 234 233
+f 234 229 232
+f 236 240 239
+f 239 237 236
+f 237 238 235
+f 240 235 238
+f 244 243 333
+f 333 334 244
+f 334 333 242
+f 242 241 334
+f 335 336 246
+f 246 245 335
+f 248 247 336
+f 336 335 248
+f 337 338 254
+f 254 338 255
+f 338 339 255
+f 255 339 340
+f 255 340 257
+f 257 340 341
+f 342 341 343
+f 257 341 342
+f 344 257 342
+f 256 257 344
+f 154 256 344
+f 273 256 154
+f 258 256 273
+f 155 254 258
+f 337 254 155
+f 339 343 253
+f 253 343 249
+f 343 341 249
+f 249 341 250
+f 341 340 250
+f 250 340 252
+f 340 339 252
+f 252 339 253
+f 261 286 274
+f 260 286 261
+f 276 262 259
+f 285 262 276
+f 287 285 286
+f 284 285 287
+f 151 284 287
+f 283 284 151
+f 283 151 270
+f 270 151 152
+f 338 343 339
+f 342 343 338
+f 337 342 338
+f 344 342 337
+f 344 337 154
+f 154 337 155
+# 462 faces, 0 coords texture
+
+# End of File
diff --git a/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/CMakeLists.txt
new file mode 100644
index 0000000000..372e7fac07
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/CMakeLists.txt
@@ -0,0 +1,5 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExamplePerreault2001Experiment SUBDIR TaskSpace
+ EXECUTABLES ExamplePerreault2001Experiment
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/ExamplePerreault2001Experiment.cpp b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/ExamplePerreault2001Experiment.cpp
new file mode 100644
index 0000000000..6f40386164
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/ExamplePerreault2001Experiment.cpp
@@ -0,0 +1,208 @@
+/**
+ * @file ExamplePerreault2001Experiment.cpp
+ *
+ * \brief Control of the MoBL 2016 upper limb model.
+ *
+ * [1] Perreault, E. J., Kirsch, R. F., & Crago, P. E. (2001). Effects of
+ * voluntary force generation on the elastic components of endpoint stiffness.
+ * Experimental Brain Research, 141(3), 312--323.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+#define USE_VISUALIZER 1
+
+Vec3 fromVectorToVec3(const Vector& v) { return Vec3(v[0], v[1], v[2]); }
+
+void findExperimentConfiguration(State& state, Model& model,
+ double thetaShoulderDeg, double thetaElbowDeg) {
+ // add orientation osensor
+ SimTK::OrientationSensors* imus = new SimTK::OrientationSensors();
+ auto humerusMX = imus->addOSensor("humerus",
+ model.updBodySet().get("humerus").getMobilizedBodyIndex(),
+ SimTK::Rotation(), 1);
+
+ auto radiusMX = imus->addOSensor("radius",
+ model.updBodySet().get("radius").getMobilizedBodyIndex(),
+ SimTK::Rotation(), 1);
+
+ // finalize observation order (to allocate ObservationIx)
+ static const int OSENSORS = 2;
+ static const char* osensor_observation_order[2] = {"humerus", "radius"};
+ imus->defineObservationOrder(OSENSORS, osensor_observation_order);
+
+ // get all ObservationIx
+ auto humerusOX = imus->getObservationIxForOSensor(humerusMX);
+ auto radiusOX = imus->getObservationIxForOSensor(radiusMX);
+
+ // move to initial target
+ SimTK::Assembler ik(model.updMultibodySystem());
+ ik.setAccuracy(1e-5);
+ ik.adoptAssemblyGoal(imus);
+ imus->moveOneObservation(humerusOX,
+ SimTK::Rotation(SimTK::BodyOrSpaceType::SpaceRotationSequence,
+ convertDegreesToRadians(-60), SimTK::XAxis,
+ convertDegreesToRadians(thetaShoulderDeg), SimTK::YAxis,
+ convertDegreesToRadians(0), SimTK::ZAxis));
+ imus->moveOneObservation(radiusOX,
+ SimTK::Rotation(SimTK::BodyOrSpaceType::SpaceRotationSequence,
+ convertDegreesToRadians(-90), SimTK::XAxis,
+ convertDegreesToRadians(thetaShoulderDeg + thetaElbowDeg),
+ SimTK::YAxis, convertDegreesToRadians(0), SimTK::ZAxis));
+
+ // setup inverse kinematics
+ state.setTime(0);
+ ik.initialize(state);
+ ik.assemble(state);
+}
+
+void perreault2001Experiment() {
+
+ const string example = "ExamplePerreault2001Experiment";
+
+ const double kp = 100;
+ const double kv = 20;
+
+ ModelVisualizer::addDirToGeometrySearchPaths(OPENSIM_GEOMETRY_DIR);
+
+ // load model
+ Model model("mobl_2016_ideal_muscles.osim");
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(AghiliModel());
+ controller->set_control_strategy("velocity");
+ model.addController(controller);
+
+ auto& marker = model.getMarkerSet().get("end_effector");
+ // here we just have to find the body to which the marker is
+ // attached, but due to OpenSim's Frame it is more difficult now
+ auto markerFrame = marker.getParentFrameName();
+ auto handBodyName = markerFrame.substr(markerFrame.find("/", 1) + 1);
+
+ // build and initialize model
+ auto& state = model.initSystem();
+ findExperimentConfiguration(state, model, 60, 120);
+ model.realizePosition(state);
+
+ // hand initial configuration
+ auto& handBody = model.getBodySet().get(handBodyName);
+ Vec3 initialOrientation =
+ handBody.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ Vec3 initialPosition = marker.getLocationInGround(state);
+
+ log_debug("initial position: {}", initialPosition);
+
+ // Set up spatial tracking for the hand
+ auto hand_orientation = new OrientationTask();
+ hand_orientation->set_priority(0);
+ hand_orientation->set_kp(Array(kp, 3));
+ hand_orientation->set_kv(Array(kv, 3));
+ auto xorient_desired = Constant(initialOrientation[0]);
+ auto yorient_desired = Constant(initialOrientation[1]);
+ auto zorient_desired = Constant(initialOrientation[2]);
+ hand_orientation->set_position_functions(0, xorient_desired);
+ hand_orientation->set_position_functions(1, yorient_desired);
+ hand_orientation->set_position_functions(2, zorient_desired);
+ hand_orientation->set_wrt_body(handBodyName);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_orientation);
+
+ auto hand_position = new StationTask();
+ hand_position->set_priority(0);
+ hand_position->set_point(marker.get_location());
+ hand_position->set_kp(Array(kp, 3));
+ hand_position->set_kv(Array(kv, 3));
+ //No acceleration error term
+ hand_position->set_ka(Array(0.0, 3));
+ auto xpos_desired = Constant(initialPosition[0]);
+ auto ypos_desired = Constant(initialPosition[1]);
+ auto zpos_desired = Sine(0.1, 2 * Pi, 0, initialPosition[2]);
+ //auto zpos_desired = Constant(initialPosition[2]);
+ hand_position->set_position_functions(0, xpos_desired);
+ hand_position->set_position_functions(1, ypos_desired);
+ hand_position->set_position_functions(2, zpos_desired);
+ //Don't use derivative of position function
+ hand_position->set_velocity_functions(0, Constant(0));
+ hand_position->set_velocity_functions(1, Constant(0));
+ hand_position->set_velocity_functions(2, Constant(0));
+ hand_position->set_wrt_body(handBodyName);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_position);
+
+
+
+#if USE_VISUALIZER == 1
+ // build and initialize model to initialize the tasks. also add a visualizer
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+
+ // put the model back in the correct initial configuration
+ findExperimentConfiguration(state, model, 60, 120);
+ model.realizePosition(state);
+
+ for (int i = 0; i < model.getCoordinateSet().getSize(); i++) {
+ if (!model.getCoordinateSet()[i].isConstrained(state))
+ cout << model.getCoordinateSet()[i].getName() << " "
+ << convertRadiansToDegrees(
+ model.getCoordinateSet()[i].getValue(state))
+ << endl;
+ }
+
+ // configure visualizer
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(false);
+ }
+#endif
+ IO::makeDir("results");
+
+ // print the complete model
+ model.print("results/" + example + ".osim");
+
+ // simulate
+ //simulate(model, state, 3.0, true);
+
+ state.setTime(0.0);
+ model.realizeDynamics(state);
+ Manager manager(model);
+ manager.setIntegratorMaximumStepSize(1e-3);
+ manager.initialize(state);
+ controller->computeControls(state, controller->_tau);
+ double end_time = 1;
+ log_debug("#####################################################");
+ log_info("\nIntegrating from {} to {}", 0.0, end_time);
+ state = manager.integrate(end_time);
+
+ // export results
+ controller->printResults(example, "results");
+ bodyKinematics->printResults(example, "results");
+}
+
+int main(int argc, char* argv[]) {
+ Logger::setLevel(Logger::Level::Info);
+ try {
+ perreault2001Experiment();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ getchar();
+ return -1;
+ }
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/mobl_2016_ideal_muscles.osim b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/mobl_2016_ideal_muscles.osim
new file mode 100644
index 0000000000..0152ea2e21
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/mobl_2016_ideal_muscles.osim
@@ -0,0 +1,9022 @@
+
+
+
+ Katherine R. Saul, Wendy M. Murray, Craig M. Goehler, Melissa Daly, Meghan E. Vidt, Dustin L. Crouch
+ Comp Meth Biomech Biomed Eng 2014
+ meters
+ N
+
+ 0 -9.80665 0
+
+
+
+
+ 0
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ thorax.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.0434587 -0.331962 0.189892
+ -0.0386 -0.1273 0.0709
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0434587 -0.331962 0.189892 -0.0386 -0.1273 0.0709
+
+ false
+
+ 0
+
+ 0.1 0.135 0.08
+
+
+
+
+
+
+ 0.156
+ -0.011096 0.0063723 0.054168
+ 0.00024259
+ 0.00025526
+ 4.442e-005
+ -1.898e-005
+ -6.994e-005
+ 5.371e-005
+
+
+
+
+ ground
+
+ 0.006325 0.00693 0.025465
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.126710904892861
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0536688754806746
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ sternoclavicular_r2
+
+ 0.0153 0.9892987 -0.14509996
+
+
+
+ 1 0
+
+
+
+
+
+ sternoclavicular_r3
+
+ -0.99447254 0 -0.10499695
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ -0.10387335 0.14590438 0.98383039
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ clavicle.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ clavicle
+
+ -0.01433 0.02007 0.135535
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0536688754806746
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.126710904892861
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ unrotscap_r3
+
+ -0.99447254 0 -0.10499695
+
+
+
+ 1 0
+
+
+
+
+
+ unrotscap_r2
+
+ 0.0153 0.9892987 -0.14509996
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0.10387335 -0.14590438 -0.98383039
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.70396
+ -0.054694 -0.035032 -0.043734
+ 0.0012429
+ 0.0011504
+ 0.0013651
+ 0.0004494
+ 0.00040922
+ 0.0002411
+
+
+
+
+ clavphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0256563401807859
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.207345117461045
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0932005826567324
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ acromioclavicular_r2
+
+ 0.15709493 0.94726859 -0.27929088
+
+
+
+ 1 0
+
+
+
+
+
+ acromioclavicular_r3
+
+ -0.75408404 0.29759402 0.58548703
+
+
+
+ 1 0
+
+
+
+
+
+ acromioclavicular_r1
+
+ 0.63769985 0.11859997 0.76109982
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ scapula.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ 3.13042 -1.54881 -1.31423
+ -0.0058 -0.0378 0.0096
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 3.13042 -1.54881 -1.31423 -0.0058 -0.0378 0.0096
+
+ false
+
+ 0
+
+ 0.033 0.04 0.035
+
+
+
+ 0
+ 0.620988 0.32882 -0.560774
+ -0.0973 -0.0428 -0.037
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.620988 0.32882 -0.560774 -0.0973 -0.0428 -0.037
+
+ false
+
+ 0
+
+ 0.04
+ 0.06
+
+
+
+ 0
+ 0.0253073 0.58835 0.151844
+ -0.0561 -0.0199 -0.0112
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0253073 0.58835 0.151844 -0.0561 -0.0199 -0.0112
+
+ false
+
+ 0
+
+ 0.008
+ 0.019
+
+
+
+ 0
+ -2.09754 -0.280823 -1.76348
+ -0.0418 -0.0519 -0.0359
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -2.09754 -0.280823 -1.76348 -0.0418 -0.0519 -0.0359
+
+ false
+
+ 0
+
+ 0.03 0.03 0.05
+
+
+
+ 0
+ 1.37532 -0.294612 2.43596
+ -0.0359 -0.0309 -0.0132
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.37532 -0.294612 2.43596 -0.0359 -0.0309 -0.0132
+
+ false
+
+ 0
+
+ 0.003
+ 0.03
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ scapula
+
+ -0.00955 -0.034 0.009
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0932005826567324
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ -0.207345117461045
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0256563401807859
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ unrothum_r1
+
+ 0.63769985 0.11859997 0.76109982
+
+
+
+ 1 0
+
+
+
+
+
+ unrothum_r3
+
+ -0.75408404 0.29759402 0.58548703
+
+
+
+ 1 0
+
+
+
+
+
+ unrothum_r2
+
+ 0.15709493 0.94726859 -0.27929088
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ scapphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.57079633 2.26892803
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ elv_angle
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.04240001 0 -0.0048
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ humphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.523598779689508
+
+ 0
+
+ 0 3.14159265
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ shoulder_elv
+
+ -0.99826136 0.0023 0.05889802
+
+
+
+ 1 0
+
+
+
+
+
+ shoulder1_r2
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ -0.05874685 0.042609 -0.99736316
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.99757
+ 0.018064 -0.140141 -0.012746
+ 0.01227763
+ 0.00255133
+ 0.01257888
+ -0.00034741
+ -0.0002325
+ 0.0012293
+
+
+
+
+ humphant1
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.57079633 0.34906585
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ shoulder_rot
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.04240001 0 -0.0048
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ humerus.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.0584685 1.00461 0.570374
+ -0.0139 -0.0127 -0.0262
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0584685 1.00461 0.570374 -0.0139 -0.0127 -0.0262
+
+ false
+
+ 0
+
+ 0.03 0.1 0.05
+
+
+
+ 0
+ 1.55093 -0.0199582 0.0596618
+ 0.0017 -0.0958 0.0011
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.55093 -0.0199582 0.0596618 0.0017 -0.0958 0.0011
+
+ false
+
+ 0
+
+ 0.0109
+ 0.12
+
+
+
+ 0
+ 1.72735 0.0759218 -2.74313
+ 0.0019 -0.0592 0.0011
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.72735 0.0759218 -2.74313 0.0019 -0.0592 0.0011
+
+ false
+
+ 0
+
+ 0.01 0.01 0.05
+
+
+
+ 0
+ 0.0380482 0.00855211 -1.30673
+ 0.0002 0.0077 0.0043
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0380482 0.00855211 -1.30673 0.0002 0.0077 0.0043
+
+ false
+
+ 0
+
+ 0.02 0.02 0.02
+
+
+
+ 0
+ -0.286583 -0.00907571 -0.0684169
+ -0.0003 0.0026 0.0038
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.286583 -0.00907571 -0.0684169 -0.0003 0.0026 0.0038
+
+ false
+
+ 0
+
+ 0.02 0.025 0.02
+
+
+
+ 0
+ -0.924501 0.288852 0.381529
+ -0.0025 0.0007 -0.0045
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.924501 0.288852 0.381529 -0.0025 0.0007 -0.0045
+
+ false
+
+ 0
+
+ 0.02 0.017 0.028
+
+
+
+ 0
+ 1.75353 0.0692896 2.74628
+ -0.0014 -0.0455 0
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.75353 0.0692896 2.74628 -0.0014 -0.0455 0
+
+ false
+
+ 0
+
+ 0.007
+ 0.07
+
+
+
+ 0
+ 1.53641 -0.0637045 1.41424
+ 0.0007 -0.0443 -0.0055
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.53641 -0.0637045 1.41424 0.0007 -0.0443 -0.0055
+
+ false
+
+ 0
+
+ 0.007
+ 0.04
+
+
+
+ 0
+ 1.55928 -0.0774926 -0.925897
+ 0.002 -0.0508 -0.0017
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.55928 -0.0774926 -0.925897 0.002 -0.0508 -0.0017
+
+ false
+
+ 0
+
+ 0.009
+ 0.07
+
+
+
+ 0
+ 0 0 0
+ -0.0086 0.0021 -0.0004
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 -0.0086 0.0021 -0.0004
+
+ false
+
+ 0
+
+ 0.02
+
+
+
+ 0
+ -0.620465 -0.310494 0.363727
+ -0.0037 0.0005 -0.0025
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.620465 -0.310494 0.363727 -0.0037 0.0005 -0.0025
+
+ false
+
+ 0
+
+ 0.03 0.02 0.02
+
+
+
+ 0
+ 1.44094 -0.0561996 1.75196
+ 0.0009 -0.0551 -0.0004
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.44094 -0.0561996 1.75196 0.0009 -0.0551 -0.0004
+
+ false
+
+ 0
+
+ 0.008
+ 0.1
+
+
+
+ 0
+ -0.305084 -0.018326 -0.686613
+ -0.0224 0.0102 0.0094
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.305084 -0.018326 -0.686613 -0.0224 0.0102 0.0094
+
+ false
+
+ 0
+
+ 0.007
+ 0.045
+
+
+
+ 0
+ -0.127235 0.276111 0.0197222
+ -0.0016 0.0092 0.0052
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.127235 0.276111 0.0197222 -0.0016 0.0092 0.0052
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ -0.128631 0.137532 0.0307178
+ 0.0019 -0.289 -0.014
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.128631 0.137532 0.0307178 0.0019 -0.289 -0.014
+
+ false
+
+ 0
+
+ 0.015 0.015 0.1
+
+
+
+ 0
+ 3.00162 -0.853466 2.57419
+ -0.0078 -0.0041 -0.0014
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 3.00162 -0.853466 2.57419 -0.0078 -0.0041 -0.0014
+
+ false
+
+ 0
+
+ 0.035 0.02 0.02
+
+
+
+ 0
+ -0.14015 -0.00628319 0.154985
+ 0.0028 -0.2919 -0.0119
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.14015 -0.00628319 0.154985 0.0028 -0.2919 -0.0119
+
+ false
+
+ 0
+
+ 0.016
+ 0.1
+
+
+
+ 0
+ 0.00750492 -0.196699 1.04929
+ 0.0134 -0.2861 -0.0008
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.00750492 -0.196699 1.04929 0.0134 -0.2861 -0.0008
+
+ false
+
+ 0
+
+ 0.02 0.02 0.02
+
+
+
+ 0
+ -2.00434 -1.00164 0.975465
+ 0.0033 0.0073 0.0003
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -2.00434 -1.00164 0.975465 0.0033 0.0073 0.0003
+
+ false
+
+ 0
+
+ 0.025 0.02 0.02
+
+
+
+ 0
+ 0 0 0
+ 0.0007 0 0.006
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0.0007 0 0.006
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ 0 0 0
+ 0.0007 0 0.006
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0.0007 0 0.006
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ -1.60832 0.0959931 0.875283
+ 0.0027 -0.1202 -0.0059
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.60832 0.0959931 0.875283 0.0027 -0.1202 -0.0059
+
+ false
+
+ 0
+
+ 0.008
+ 0.1
+
+
+
+ 0
+ -0.161094 -0.110828 0.61453
+ 0.003 -0.2872 -0.0069
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.161094 -0.110828 0.61453 0.003 -0.2872 -0.0069
+
+ false
+
+ 0
+
+ 0.018 0.025 0.035
+
+
+
+
+
+
+ 1.1053
+ 0.00971783 -0.0959509 0.024286
+ 0.00541309
+ 0.00115318
+ 0.00494361
+ 0.00031686
+ -7.615e-005
+ 0.00109169
+
+
+
+
+ humerus
+
+ 0.0061 -0.2904 -0.0123
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -1.99870688474894e-008
+
+ 0
+
+ 0 2.26892803
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ elbow_flexion
+
+ 0.04940001 0.03660001 0.99810825
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.99810825 0 -0.04940001
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ ulna.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ 1.39138 0.0689405 1.52245
+ -0.0012 -0.2092 0.0428
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.39138 0.0689405 1.52245 -0.0012 -0.2092 0.0428
+
+ false
+
+ 0
+
+ 0.007
+ 0.1
+
+
+
+
+
+
+ 0.23359
+ 0.0336341 -0.181559 0.0156
+ 0.00043855
+ 8.859e-005
+ 0.00040258
+ 3.014e-005
+ -4.24e-006
+ 6.418e-005
+
+
+
+
+ ulna
+
+ 0.0004 -0.011503 0.019999
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -2e-008
+
+ 0
+
+ -1.57079633 1.57079633
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ pro_sup
+
+ -0.01716099 0.99266564 -0.11966796
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ -0.11966796 0 0.01716099
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ radius.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 1.44775 0.304036 -2.44102
+ 0.0045 -0.0437 0.0059
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.44775 0.304036 -2.44102 0.0045 -0.0437 0.0059
+
+ false
+
+ 0
+
+ 0.008
+ 0.04
+
+
+
+ 0
+ -0.986635 -0.148877 0.222704
+ -0.0163 -0.2417 0.0349
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.986635 -0.148877 0.222704 -0.0163 -0.2417 0.0349
+
+ false
+
+ 0
+
+ 0.006
+ 0.009
+
+
+
+ 0
+ -1.60762 -0.0127409 -2.69025
+ 0.0281 -0.1986 0.0288
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.60762 -0.0127409 -2.69025 0.0281 -0.1986 0.0288
+
+ false
+
+ 0
+
+ 0.01
+ 0.1
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1e-005
+ 1e-005
+ 1e-005
+ 0
+ 0
+ 0
+
+
+
+
+ radius
+
+ 0.018 -0.242 0.025
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -0.17453293 0.43633231
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.22173048 1.22173048
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ deviation
+
+ -0.819064 -0.135611 -0.557444
+
+
+
+ -0.174533 0 0.436332
+ -0.174533 0 0.436332
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+ flexion
+
+ 0.95642673 -0.25220693 0.14710396
+
+
+
+ -1.5708 1.5708
+ -0.785398 0.785398
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ lunate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastSCAPHOIDw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastPISIFORMw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastTRIQUETRALw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ -0.250804 0.285536 0.232827
+ 0.0007 -0.0135 0.0047
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.250804 0.285536 0.232827 0.0007 -0.0135 0.0047
+
+ false
+
+ 0
+
+ 0.05 0.02 0.013
+
+
+
+ 0
+ 1.53833 0.234398 0.731118
+ 0.0222 -0.0096 0.0208
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.53833 0.234398 0.731118 0.0222 -0.0096 0.0208
+
+ false
+
+ 0
+
+ 0.008
+ 0.016
+
+
+
+ 0
+ 1.31266 -0.11781 -0.116239
+ 0.0126 -0.0095 0.0186
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.31266 -0.11781 -0.116239 0.0126 -0.0095 0.0186
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -1.55596 -0.15324 -0.100007
+ 0.0032 -0.0045 -0.019
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.55596 -0.15324 -0.100007 0.0032 -0.0045 -0.019
+
+ false
+
+ 0
+
+ 0.001
+ 0.0025
+
+
+
+ 0
+ -1.57376 -0.0797616 0.39235
+ -0.0123 -0.0124 -0.0171
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57376 -0.0797616 0.39235 -0.0123 -0.0124 -0.0171
+
+ false
+
+ 0
+
+ 0.0068
+ 0.008
+
+
+
+ 0
+ -0.0315905 0.0996583 0.0633554
+ 0.0057 -0.018 -0.0041
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.0315905 0.0996583 0.0633554 0.0057 -0.018 -0.0041
+
+ false
+
+ 0
+
+ 0.025 0.014 0.012
+
+
+
+ 0
+ 0.00837758 -0.0816814 -0.0171042
+ 0.0012 -0.0057 -0.0003
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.00837758 -0.0816814 -0.0171042 0.0012 -0.0057 -0.0003
+
+ false
+
+ 0
+
+ 0.025 0.013 0.012
+
+
+
+ 0
+ -1.46747 -0.194604 0.121824
+ -0.0022 -0.0069 0.0032
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.46747 -0.194604 0.121824 -0.0022 -0.0069 0.0032
+
+ false
+
+ 0
+
+ 0.025 0.013 0.012
+
+
+
+ 0
+ 2.36318 0.193033 -0.26913
+ -0.0128 -0.0133 0.0148
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.36318 0.193033 -0.26913 -0.0128 -0.0133 0.0148
+
+ false
+
+ 0
+
+ 0.008
+ 0.012
+
+
+
+ 0
+ 1.98392 0.100531 0.523075
+ -0.0098 -0.0137 0.0166
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.98392 0.100531 0.523075 -0.0098 -0.0137 0.0166
+
+ false
+
+ 0
+
+ 0.0105
+ 0.011
+
+
+
+ 0
+ 1.99317 0.19792 0.368264
+ -0.0007 -0.0117 0.0191
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.99317 0.19792 0.368264 -0.0007 -0.0117 0.0191
+
+ false
+
+ 0
+
+ 0.009
+ 0.012
+
+
+
+ 0
+ 1.69768 0.0897099 0.00767945
+ 0.009 -0.0149 0.0211
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.69768 0.0897099 0.00767945 0.009 -0.0149 0.0211
+
+ false
+
+ 0
+
+ 0.009
+ 0.012
+
+
+
+ 0
+ 2.9627 0.159349 0.117984
+ -0.0167 -0.0022 0.0048
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.9627 0.159349 0.117984 -0.0167 -0.0022 0.0048
+
+ false
+
+ 0
+
+ 0.018 0.014 0.008
+
+
+
+ 0
+ -0.16633 -0.082205 -0.0659735
+ 0.017 -0.025 -0.0033
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.16633 -0.082205 -0.0659735 0.017 -0.025 -0.0033
+
+ false
+
+ 0
+
+ 0.016 0.01 0.01
+
+
+
+
+
+
+ 0.5819
+ -0.00301314 -0.0424993 -0.00112205
+ 0.00011
+ 6e-005
+ 0.00015
+ 9e-007
+ -2e-007
+ 1.2e-005
+
+
+
+
+ proximal_row
+
+ 0.003992 -0.015054 0.002327
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ wrist_hand_r1
+
+ 0.8991357 -0.34905288 -0.26403991
+
+
+
+ 1 0
+
+
+
+
+
+ wrist_hand_r3
+
+ 0.99711853 0.01069999 -0.07510096
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0.02903943 -0.19575313 0.35766784
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ sdfast_1seg_hand_fr_c_5mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_4mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_3mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_2mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_trapezium.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_trapezoid.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_hamate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ capitate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_thumbprox.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_thumbdist.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_1mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.593936 1.50011 -2.16578
+ 0.0182 -0.0659 0.0087
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -2.16578 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.593936 1.50011 -2.23559
+ 0.0182 -0.0659 0.0087
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -2.23559 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.593936 1.50011 -1.99125
+ 0.0182 -0.0659 0.0087
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -1.99125 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 1.48667 -1.29661 2.43072
+ 0.0206 -0.068 0.0044
+ false
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.48667 -1.29661 2.43072 0.0206 -0.068 0.0044
+
+ false
+
+ 0
+
+ 0.005 0.005 0.03
+
+
+
+ 0
+ 0.770388 1.32837 1.5708
+ 0.0007 -0.0655 0.0092
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.5708 0.0007 -0.0655 0.0092
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.770388 1.32837 1.5708
+ 0.0046 -0.0662 0.0099
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.5708 0.0046 -0.0662 0.0099
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.770388 1.32837 1.46608
+ 0.0007 -0.0655 0.0092
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.46608 0.0007 -0.0655 0.0092
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -2.48535
+ -0.0139 -0.0642 0.0033
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -2.48535 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -2.48535
+ -0.0139 -0.0642 0.0033
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -2.48535 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -3.09621
+ -0.0139 -0.0642 0.0033
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -3.09621 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 0.470541 0.975639 -2.12162
+ -0.0235 -0.0561 -0.0057
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -2.12162 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.013
+ 0.012
+
+
+
+ 0
+ 0.470541 0.975639 -2.34852
+ -0.0235 -0.0561 -0.0057
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -2.34852 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.470541 0.975639 -1.68529
+ -0.0235 -0.0561 -0.0057
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -1.68529 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.01
+ 0.012
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.0055
+ 0.012
+
+
+
+ 0
+ -1.63171 1.34286 2.11639
+ 0.0291 -0.0821 -0.045
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.63171 1.34286 2.11639 0.0291 -0.0821 -0.045
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ -1.63171 1.34286 2.11639
+ 0.0291 -0.0821 -0.045
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.63171 1.34286 2.11639 0.0291 -0.0821 -0.045
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 2.2513 -1.37008 1.18159
+ 0.0306 -0.0911 -0.0223
+ false
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.2513 -1.37008 1.18159 0.0306 -0.0911 -0.0223
+
+ false
+
+ 0
+
+ 0.004
+ 0.01
+
+
+
+ 0
+ 1.35525 -1.38387 -0.557109
+ 0.0295 -0.0815 -0.0441
+ false
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.35525 -1.38387 -0.557109 0.0295 -0.0815 -0.0441
+
+ false
+
+ 0
+
+ 0.003
+ 0.01
+
+
+
+ 0
+ 0.321315 0.11013 -0.834791
+ 0.0402 -0.0405 -0.0271
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.321315 0.11013 -0.834791 0.0402 -0.0405 -0.0271
+
+ false
+
+ 0
+
+ 0.0085
+ 0.02
+
+
+
+ 0
+ 0.332136 -0.026529 -0.257611
+ 0.0396 -0.0713 -0.0365
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.332136 -0.026529 -0.257611 0.0396 -0.0713 -0.0365
+
+ false
+
+ 0
+
+ 0.0045
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.714189 1.28282 -0.203331
+ 0.019 -0.0814 -0.0494
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.714189 1.28282 -0.203331 0.019 -0.0814 -0.0494
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.714189 1.28282 -0.203331
+ 0.019 -0.0814 -0.0494
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.714189 1.28282 -0.203331 0.019 -0.0814 -0.0494
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.75311 0.925897 -0.167377
+ 0.0094 -0.0778 -0.0469
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.75311 0.925897 -0.167377 0.0094 -0.0778 -0.0469
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.75311 0.925897 -0.167377
+ 0.0094 -0.0778 -0.0469
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.75311 0.925897 -0.167377 0.0094 -0.0778 -0.0469
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.51687
+ -0.0154 -0.0784 -0.0329
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.51687 -0.0154 -0.0784 -0.0329
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.79612
+ -0.0153 -0.0786 -0.0329
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.79612 -0.0153 -0.0786 -0.0329
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.08053
+ -0.0152 -0.0785 -0.0328
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.08053 -0.0152 -0.0785 -0.0328
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.979304 0.65031 -0.620814
+ 0.0007 -0.0741 -0.0457
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.979304 0.65031 -0.620814 0.0007 -0.0741 -0.0457
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.979304 0.65031 -0.620814
+ 0.007 -0.0741 -0.0457
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.979304 0.65031 -0.620814 0.007 -0.0741 -0.0457
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.633555
+
+
+
+ shoulder_elv
+
+ sternoclavicular_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 3.14159
+ 0 0.322013
+
+
+
+ shoulder_elv
+
+ sternoclavicular_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.633555
+
+
+
+ shoulder_elv
+
+ unrotscap_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 3.14159
+ 0 -0.322013
+
+
+
+ shoulder_elv
+
+ unrotscap_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.466003
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r1
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.128282
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 1.03673
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.466003
+
+
+
+ shoulder_elv
+
+ unrothum_r1
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.128282
+
+
+
+ shoulder_elv
+
+ unrothum_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -1.03673
+
+
+
+ shoulder_elv
+
+ unrothum_r3
+
+ 1
+
+
+
+ false
+
+
+
+ -1.5708 3.14159
+ 1.5708 -3.14159
+
+
+
+ elv_angle
+
+ shoulder1_r2
+
+ 1
+
+
+
+ false
+
+
+
+ -0.174533 0 0.436332
+ -0.261799 0 0.436332
+
+
+
+ deviation
+
+ wrist_hand_r1
+
+ 1
+
+
+
+ false
+
+
+
+ -1.22173 1.22173
+ -0.610865 0.610865
+
+
+
+ flexion
+
+ wrist_hand_r3
+
+ 1
+
+
+
+
+
+
+
+
+
+ false
+
+ shoulder_elv
+
+ 100
+
+ 150
+
+ 100
+
+ 30
+
+ 0
+
+ 542.8423
+
+
+
+ false
+
+ shoulder_elv
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ elv_angle
+
+ 100
+
+ 100
+
+ 100
+
+ -60
+
+ 0
+
+ 545.4471
+
+
+
+ false
+
+ elv_angle
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ shoulder_rot
+
+ 100
+
+ -10
+
+ 100
+
+ -60
+
+ 0
+
+ 485.466
+
+
+
+ false
+
+ shoulder_rot
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ elbow_flexion
+
+ 0.3037
+
+ 85
+
+ 100
+
+ 14
+
+ 0
+
+ 139.5813
+
+
+
+ false
+
+ elbow_flexion
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ pro_sup
+
+ 50
+
+ 60
+
+ 50
+
+ -60
+
+ 0
+
+ 430.1186
+
+
+
+ false
+
+ pro_sup
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ deviation
+
+ 52.5961
+
+ 20
+
+ 487.176
+
+ -6
+
+ 0
+
+ 39.1586
+
+
+
+ false
+
+ deviation
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ flexion
+
+ 200
+
+ 60
+
+ 135.3232
+
+ -60
+
+ 0
+
+ 92.916
+
+
+
+ false
+
+ flexion
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.00043633
+
+ 1
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00896 -0.11883 0.00585
+ humerus
+
+
+ 0.01623 -0.11033 0.00412
+ humerus
+
+
+ 0.04347 -0.03252 0.00099
+ scapula
+
+
+ -0.014 0.01106 0.08021
+ clavicle
+
+
+
+
+
+
+
+
+ delt2hum
+ hybrid
+ -1 -1
+
+
+ DELT1hh
+ hybrid
+ 2 3
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1218.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.05573 0.00122 -0.02512
+ scapula
+
+
+ -0.07247 -0.03285 0.01233
+ scapula
+
+
+ 0.00206 -0.07602 0.01045
+ humerus
+
+
+
+
+
+
+
+
+ Delt3
+ hybrid
+ 1 2
+
+
+ delt3hum
+ hybrid
+ -1 -1
+
+
+ DELT_TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 201.6
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00256 0.01063 0.02593
+ humerus
+
+
+ -0.01918 0.00127 -0.01271
+ scapula
+
+
+ -0.044 -0.01512 -0.05855
+ scapula
+
+
+
+
+
+
+
+
+ SUPSP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 499.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00887 0.00484 0.02448
+ humerus
+
+
+ -0.07382 -0.05476 -0.04781
+ scapula
+
+
+
+
+
+
+
+
+ INFSP
+ hybrid
+ -1 -1
+
+
+ INFSP_and_TMIN_hum_head
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1075.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01403 0.0084 -0.01331
+ humerus
+
+
+ -0.01831 -0.05223 -0.02457
+ scapula
+
+
+ -0.07246 -0.03943 -0.06475
+ scapula
+
+
+
+
+
+
+
+
+ SUBSCAP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1306.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0011 -0.01264 0.02156
+ humerus
+
+
+ -0.09473 -0.07991 -0.04737
+ scapula
+
+
+ -0.09643 -0.08121 -0.05298
+ scapula
+
+
+
+
+
+
+
+
+ TMIN
+ hybrid
+ 1 2
+
+
+ INFSP_and_TMIN_hum_head
+ hybrid
+ 1 2
+
+
+ TMINhum
+ hybrid
+ 1 2
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 269.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00998 -0.05419 -0.00568
+ humerus
+
+
+ -0.10264 -0.10319 -0.05829
+ scapula
+
+
+ -0.10489 -0.10895 -0.07117
+ scapula
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 144
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01169 -0.04191 0.0078
+ humerus
+
+
+ 0.0171333 -0.037 -0.00337
+ humerus
+
+
+ 0 3.14159
+ 0.01615 0.02205
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04045 -0.01975
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.00577 0.00863
+
+
+ shoulder_elv
+
+
+ 0.00636333 -0.00732333 0.119273
+ ground
+
+
+ 0 3.14159
+ 0.00958 -0.00972
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.01509 0.03151
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.12664 0.08244
+
+
+ shoulder_elv
+
+
+ 0.00321 -0.00013 0.05113
+ clavicle
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC12hum
+ hybrid
+ 2 3
+
+
+ PEC1hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 444.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01274 -0.04289 0.00785
+ humerus
+
+
+ 0.0155133 -0.04223 -0.00447
+ humerus
+
+
+ 0 3.14159
+ 0.01453 0.02043
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04568 -0.02498
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.00687 0.00753
+
+
+ shoulder_elv
+
+
+ 0.0203967 -0.03445 0.123117
+ ground
+
+
+ 0 3.14159
+ 0.02018 0.02148
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04165 0.00155
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.1269 0.1042
+
+
+ shoulder_elv
+
+
+ 0.03091 -0.03922 0.09705
+ ground
+
+
+ 0.02769 -0.04498 0.02271
+ ground
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC12hum
+ hybrid
+ 2 3
+
+
+ TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+ PEC23hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 658.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01269 -0.04375 0.0075
+ humerus
+
+
+ 0.0142392 -0.0496515 -0.00936368
+ humerus
+
+
+ 0 0.747517 3.14159
+ 0.01243 0.014912 0.01833
+
+
+ shoulder_elv
+
+
+ 0 3.13149
+ -0.05157 -0.040096
+
+
+ shoulder_elv
+
+
+ 0 0.623056 2.29124 3.12533
+ -0.01807 -0.008102 0.000123 -0.000324
+
+
+ shoulder_elv
+
+
+ 0.02984 -0.0697393 0.1151
+ ground
+
+
+ 0 3.14159
+ 0.02984 0.02984
+
+
+ shoulder_elv
+
+
+ 0.0101016 1.59605 3.14159
+ -0.070778 -0.059781 -0.0269
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.1151 0.1151
+
+
+ shoulder_elv
+
+
+ 0.0525 -0.08417 0.08935
+ ground
+
+
+ 0.05724 -0.11654 0.03787
+ ground
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC3hum
+ hybrid
+ 2 3
+
+
+ PEC23hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 498.1
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0105 -0.03415 -0.00653
+ humerus
+
+
+ -0.07982 -0.0799433 -0.02428
+ scapula
+
+
+ 0 3.14159
+ -0.07947 -0.08157
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.08581 -0.05061
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.02188 -0.03628
+
+
+ shoulder_elv
+
+
+ -0.111183 -0.0893233 -0.06022
+ scapula
+
+
+ 0 3.14159
+ -0.11215 -0.10635
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.09779 -0.04699
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.05322 -0.09522
+
+
+ shoulder_elv
+
+
+ -0.11828 -0.10118 0.03316
+ ground
+
+
+ -0.09578 -0.11724 0.00882
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 290.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00968 -0.04071 -0.00611
+ humerus
+
+
+ -0.07875 -0.0971167 -0.02023
+ scapula
+
+
+ 0 3.14159
+ -0.0764 -0.0905
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.1022 -0.0717
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.01808 -0.03098
+
+
+ shoulder_elv
+
+
+ -0.10544 -0.128957 -0.0645967
+ scapula
+
+
+ 0 3.14159
+ -0.10054 -0.12994
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.13969 -0.07529
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.05258 -0.12468
+
+
+ shoulder_elv
+
+
+ -0.10992 -0.16908 0.02878
+ ground
+
+
+ -0.07186 -0.18818 0.00815
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 317.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01208 -0.03922 -0.00416
+ humerus
+
+
+ -0.06598 -0.127347 -0.0241833
+ scapula
+
+
+ 0 3.14159
+ -0.05678 -0.11198
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.13303 -0.09893
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.0213 -0.0386
+
+
+ shoulder_elv
+
+
+ -0.10059 -0.16313 -0.0590767
+ scapula
+
+
+ 0 3.14159
+ -0.09449 -0.13109
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.17553 -0.10113
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04406 -0.13416
+
+
+ shoulder_elv
+
+
+ -0.11157 -0.19387 0.05532
+ ground
+
+
+ -0.07117 -0.24858 0.00907
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 189
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0125 -0.04127 -0.02652
+ scapula
+
+
+ 0.00483 -0.06958 -0.01563
+ scapula
+
+
+ 0.00743 -0.15048 -0.00782
+ humerus
+
+
+
+
+
+
+
+
+ CORBhum
+ hybrid
+ -1 -1
+
+
+ TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 208.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.04565 -0.04073 -0.01377
+ scapula
+
+
+ -0.02714 -0.11441 -0.00664
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+ TRIlonghh
+ hybrid
+ -1 -1
+
+
+ TRIlongglen
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 771.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00599 -0.12646 0.00428
+ humerus
+
+
+ -0.02344 -0.14528 0.00928
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 717.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00838 -0.13695 -0.00906
+ humerus
+
+
+ -0.02601 -0.15139 -0.0108
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 717.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00744 -0.28359 0.00979
+ humerus
+
+
+ -0.02532 -0.00124 0.006
+ ulna
+
+
+
+
+
+
+
+
+ ANC
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 283.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00996 -0.06096 0.00075
+ radius
+
+
+ 0.01201 -0.0517 -0.00107
+ radius
+
+
+ -0.0136 -0.03384 0.02013
+ ulna
+
+
+
+
+
+
+
+
+ SUP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 379.6
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0068 -0.1739 -0.0036
+ humerus
+
+
+ 0.01894 -0.28559 -0.01105
+ humerus
+ 0 0.813149
+ elbow_flexion
+
+
+ 0.00498 -0.01463 0.00128
+ ulna
+ 0 0.813149
+ elbow_flexion
+
+
+ -0.0032 -0.0239 0.0009
+ ulna
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1177.37
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0098 -0.19963 0.00223
+ humerus
+
+
+ 0.03577 -0.12742 0.02315
+ radius
+
+
+ 0.0419 -0.221 0.0224
+ radius
+
+
+
+
+
+
+
+
+ Elbow_BIC_BRD
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 276
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0073 -0.2609 0.0091
+ humerus
+
+
+ 0.03195 -0.13463 0.02779
+ radius
+
+
+ 0.04243 -0.23684 0.0362
+ radius
+
+
+ 0.01717 -0.02122 0.00583
+ hand
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 337.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01349 -0.29048 0.01698
+ humerus
+
+
+ 0.02905 -0.13086 0.02385
+ radius
+
+
+ 0.03549 -0.22805 0.03937
+ radius
+
+
+ 0.005 -0.01136 0.0085
+ hand
+
+
+
+
+
+
+
+
+ ECRB
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 252.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00083 -0.28955 0.0188
+ humerus
+
+
+ -0.01391 -0.03201 0.02947
+ ulna
+
+
+ -0.01705 -0.05428 0.02868
+ ulna
+
+
+ -0.01793 -0.09573 0.03278
+ ulna
+
+
+ -0.01421 -0.22696 0.03481
+ radius
+
+
+ -0.02251 -0.01401 -0.00128
+ hand
+
+
+
+
+
+
+
+
+ ECU
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 192.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00758 -0.27806 -0.03705
+ humerus
+
+
+ 0.0211 -0.21943 0.00127
+ radius
+
+
+ 0.01124 -0.01844 -0.00418
+ hand
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ FCR
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 407.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00219 -0.2774 -0.0388
+ humerus
+
+
+ 0.00949 -0.1841 0.0005
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.00279 0.00949 0.01869
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.1838 -0.1841 -0.1821
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.0069 0.0005 0.0002
+
+
+ pro_sup
+
+
+ 0.01082 -0.22327 0.00969
+ radius
+
+
+ -0.02036 -0.01765 -0.00752
+ hand
+
+
+
+
+
+
+
+
+ FCU
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 479.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00457 -0.27519 -0.03865
+ humerus
+
+
+ 0.02531 -0.23915 -0.00276
+ radius
+
+
+ 0.00917 -0.01898 -0.01754
+ hand
+
+
+ 0.00227 -0.03096 0.00493
+ hand
+
+
+
+
+
+
+
+
+ PL
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 101
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0036 -0.2759 -0.0365
+ humerus
+
+
+ 0.00846 -0.03373 -0.01432
+ ulna
+
+
+ 0.01219 -0.06516 -0.00219
+ ulna
+
+
+ -1.5708 1.5708
+ 0.01884 0.00554
+
+
+ pro_sup
+
+
+ -1.5708 1.5708
+ -0.06086 -0.06946
+
+
+ pro_sup
+
+
+ -1.5708 1.5708
+ 0.00506 -0.00944
+
+
+ pro_sup
+
+
+ 0.0236 -0.0934 0.0094
+ radius
+ -1.5708 0.509636
+ pro_sup
+
+
+ 0.0254 -0.1088 0.0198
+ radius
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 557.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.03245 -0.19998 0.01962
+ radius
+
+
+ 0.00193 -0.20972 0.03632
+ ulna
+
+
+
+
+
+
+
+
+ PQ2
+ hybrid
+ -1 -1
+
+
+ PQ1
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 284.7
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00421 -0.27598 -0.03864
+ humerus
+
+
+ 0.01377 -0.18718 0.00205
+ radius
+
+
+ -0.00235 -0.01393 -0.01376
+ hand
+
+
+ -0.01995 -0.04281 -0.00742
+ hand
+
+
+ -0.02044 -0.05981 -0.01878
+ hand
+
+
+ -0.01713 -0.07245 -0.02753
+ hand
+
+
+ -0.01156 -0.07271 -0.03656
+ hand
+
+
+ -0.01059 -0.07271 -0.03796
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ _5rdmcp_FDS
+ hybrid
+ 4 5
+
+
+ Fifthpm_FDS
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 75.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00479 -0.2788 -0.03731
+ humerus
+
+
+ 0.01571 -0.18666 0.00267
+ radius
+
+
+ -0.00082 -0.01344 -0.01359
+ hand
+
+
+ -0.00977 -0.05179 4e-005
+ hand
+
+
+ -0.01323 -0.0667 -0.0102
+ hand
+
+
+ -0.00788 -0.08027 -0.02503
+ hand
+
+
+ -0.00299 -0.08125 -0.03395
+ hand
+
+
+ 0.00062 -0.08092 -0.03892
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_FDS
+ hybrid
+ 4 5
+
+
+ Fourthpm_FDS
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 171.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00669 -0.02713 -0.00191
+ ulna
+
+
+ 0.01899 -0.18706 0.00424
+ radius
+
+
+ 0.0068 -0.01377 -0.01399
+ hand
+
+
+ 0.00471 -0.03332 -0.00132
+ hand
+
+
+ 0.00542 -0.0566 0.0006
+ hand
+
+
+ 0.00555 -0.07224 -0.00338
+ hand
+
+
+ 0.01167 -0.0881 -0.0167
+ hand
+
+
+ 0.01301 -0.0887 -0.02977
+ hand
+
+
+ 0.01568 -0.08577 -0.03765
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ _3rdmcp_FDS
+ hybrid
+ 5 6
+
+
+ Thirdpm_FDS
+ hybrid
+ 7 8
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 258.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00676 -0.02819 -0.00137
+ ulna
+
+
+ 0.02145 -0.18623 0.00552
+ radius
+
+
+ 0.00889 -0.01366 -0.01387
+ hand
+
+
+ 0.01061 -0.03787 0.00024
+ hand
+
+
+ 0.01782 -0.05108 0.00418
+ hand
+
+
+ 0.01849 -0.07297 -0.00375
+ hand
+
+
+ 0.02678 -0.08714 -0.01804
+ hand
+
+
+ 0.02667 -0.0874 -0.02678
+ hand
+
+
+ 0.0266 -0.08633 -0.02903
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_FDS
+ hybrid
+ 5 6
+
+
+ Secondpm_FDS
+ hybrid
+ 7 8
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 162.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00628 -0.03214 0.00254
+ ulna
+
+
+ 0.01409 -0.18516 0.00861
+ radius
+
+
+ -0.00088 -0.01027 -0.01188
+ hand
+
+
+ -0.01855 -0.04646 -0.00733
+ hand
+
+
+ -0.01808 -0.05841 -0.0156
+ hand
+
+
+ -0.01428 -0.07289 -0.02683
+ hand
+
+
+ -0.0092 -0.07483 -0.03684
+ hand
+
+
+ -0.00312 -0.07405 -0.04165
+ hand
+
+
+ 0.00446 -0.07059 -0.04657
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _5rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Fifthpm_FDP
+ hybrid
+ 6 7
+
+
+ Fifthmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 236.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00502 -0.03374 0.00273
+ ulna
+
+
+ 0.0158 -0.18629 0.00803
+ radius
+
+
+ 0.00106 -0.01177 -0.01184
+ hand
+
+
+ -0.00855 -0.05542 0.00088
+ hand
+
+
+ -0.01079 -0.06588 -0.00817
+ hand
+
+
+ -0.00547 -0.08154 -0.02256
+ hand
+
+
+ -0.00056 -0.0823 -0.03367
+ hand
+
+
+ 0.00609 -0.07837 -0.04238
+ hand
+
+
+ 0.01211 -0.0738 -0.04858
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Fourthpm_FDP
+ hybrid
+ 6 7
+
+
+ Fourthmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 172.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00522 -0.03327 0.0021
+ ulna
+
+
+ 0.01906 -0.18644 0.00785
+ radius
+
+
+ 0.00335 -0.0128 -0.01144
+ hand
+
+
+ 0.00302 -0.03447 -0.00611
+ hand
+
+
+ 0.00252 -0.05863 0.00122
+ hand
+
+
+ 0.00285 -0.06985 -0.00133
+ hand
+
+
+ 0.00863 -0.08779 -0.01815
+ hand
+
+
+ 0.01002 -0.08766 -0.02964
+ hand
+
+
+ 0.01633 -0.08157 -0.04435
+ hand
+
+
+ 0.01909 -0.07663 -0.05229
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _3rdmcp_FDP
+ hybrid
+ 5 6
+
+
+ Thirdpm_FDP
+ hybrid
+ 7 8
+
+
+ Thirdmd_flex
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 212.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00647 -0.03176 0.0028
+ ulna
+
+
+ 0.0208 -0.1856 0.00915
+ radius
+
+
+ 0.00896 -0.01168 -0.01212
+ hand
+
+
+ 0.01922 -0.05542 0.00438
+ hand
+
+
+ 0.02073 -0.07021 -0.00286
+ hand
+
+
+ 0.02904 -0.08588 -0.01782
+ hand
+
+
+ 0.02924 -0.08672 -0.02769
+ hand
+
+
+ 0.02914 -0.08235 -0.03979
+ hand
+
+
+ 0.02847 -0.07771 -0.04766
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Secondpm_FDP
+ hybrid
+ 6 7
+
+
+ Secondmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 197.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0004 -0.28831 0.0187
+ humerus
+
+
+ 0.0013 -0.03888 0.01405
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.0121 0.0013 -0.0095
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04018 -0.03888 -0.03508
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01055 0.01405 0.01316
+
+
+ pro_sup
+
+
+ 0.00993 -0.22304 0.03618
+ radius
+
+
+ -0.02464 -0.04402 0.00169
+ hand
+
+
+ -0.02381 -0.04734 0.00077
+ hand
+
+
+ -0.02395 -0.06613 -0.01001
+ hand
+
+
+ -0.01798 -0.07847 -0.02711
+ hand
+
+
+ -0.01178 -0.07877 -0.03779
+ hand
+
+
+ -0.0015 -0.07586 -0.04586
+ hand
+
+
+ 0.00201 -0.07487 -0.04794
+ hand
+
+
+
+
+
+
+
+
+ EDCL
+ hybrid
+ 3 4
+
+
+ _5rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Fifthpm_ext
+ hybrid
+ 7 8
+
+
+ Fifthmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 39.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00156 -0.28936 0.01782
+ humerus
+
+
+ 0.0026 -0.03991 0.01552
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.0134 0.0026 -0.0082
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04121 -0.03991 -0.03611
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01202 0.01552 0.01463
+
+
+ pro_sup
+
+
+ 0.00882 -0.22366 0.04284
+ radius
+
+
+ -0.01564 -0.0555 0.00934
+ hand
+
+
+ -0.01427 -0.05819 0.01161
+ hand
+
+
+ -0.0158 -0.07216 -0.00421
+ hand
+
+
+ -0.00825 -0.08735 -0.0226
+ hand
+
+
+ -0.00272 -0.08806 -0.03409
+ hand
+
+
+ 0.00763 -0.08026 -0.04658
+ hand
+
+
+ 0.01069 -0.07809 -0.04941
+ hand
+
+
+
+
+
+
+
+
+ EDCR
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Fourthpm_ext
+ hybrid
+ 7 8
+
+
+ Fourthmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 109.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00051 -0.28984 0.01949
+ humerus
+
+
+ 0.00316 -0.03948 0.01528
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.01396 0.00316 -0.00764
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04078 -0.03948 -0.03568
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01178 0.01528 0.01439
+
+
+ pro_sup
+
+
+ 0.0144 -0.22323 0.04223
+ radius
+
+
+ 0.00039 -0.05274 0.01491
+ hand
+
+
+ -0.00087 -0.05574 0.01452
+ hand
+
+
+ 0.00186 -0.07718 0.00597
+ hand
+
+
+ 0.01007 -0.09313 -0.01774
+ hand
+
+
+ 0.01321 -0.09558 -0.03056
+ hand
+
+
+ 0.01857 -0.08525 -0.04759
+ hand
+
+
+ 0.02056 -0.07993 -0.05341
+ hand
+
+
+ 0.02195 -0.07701 -0.05663
+ hand
+
+
+
+
+
+
+
+
+ EDCM
+ hybrid
+ 1 4
+
+
+ Thirdmd_ext
+ hybrid
+ 9 10
+
+
+ Thirdpm_ext
+ hybrid
+ 7 8
+
+
+ _3rdmcp_ext
+ hybrid
+ 5 6
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 94.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00065 -0.28898 0.01869
+ humerus
+
+
+ 0.00228 -0.03918 0.01483
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.01308 0.00228 -0.00852
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04048 -0.03918 -0.03538
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01133 0.01483 0.01394
+
+
+ pro_sup
+
+
+ 0.01533 -0.22314 0.04196
+ radius
+
+
+ 0.01543 -0.0468 0.01639
+ hand
+
+
+ 0.01897 -0.05654 0.01438
+ hand
+
+
+ 0.01994 -0.07678 0.00594
+ hand
+
+
+ 0.02945 -0.09162 -0.01245
+ hand
+
+
+ 0.03121 -0.09349 -0.02905
+ hand
+
+
+ 0.03013 -0.08487 -0.04268
+ hand
+
+
+ 0.02929 -0.08103 -0.04966
+ hand
+
+
+
+
+
+
+
+
+ EDCI
+ hybrid
+ 3 4
+
+
+ _2rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Secondpm_ext
+ hybrid
+ 7 8
+
+
+ Secondmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 48.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00089 -0.28919 0.01847
+ humerus
+
+
+ -0.00977 -0.03907 0.03085
+ ulna
+
+
+ -0.00755 -0.08267 0.03646
+ ulna
+
+
+ 0.00454 -0.22641 0.03678
+ radius
+
+
+ -0.02059 -0.01032 0.00372
+ hand
+
+
+ -0.02563 -0.04722 0.00023
+ hand
+
+
+ -0.02549 -0.06511 -0.01098
+ hand
+
+
+ -0.01933 -0.0781 -0.02718
+ hand
+
+
+ -0.01346 -0.07892 -0.03894
+ hand
+
+
+ -0.00216 -0.07521 -0.04589
+ hand
+
+
+ 0.00132 -0.07345 -0.04803
+ hand
+
+
+
+
+
+
+
+
+ EDM
+ hybrid
+ 4 5
+
+
+ Fifthmd_ext
+ hybrid
+ 10 11
+
+
+ Fifthpm_ext
+ hybrid
+ 8 9
+
+
+ _5rdmcp_ext
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 72.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00394 -0.16652 0.03682
+ ulna
+
+
+ 0.00171 -0.17469 0.04049
+ ulna
+
+
+ 0.01076 -0.22783 0.03664
+ radius
+
+
+ 0.00388 -0.02234 0.01184
+ hand
+
+
+ 0.01693 -0.0564 0.01377
+ hand
+
+
+ 0.01735 -0.07692 0.00581
+ hand
+
+
+ 0.02765 -0.09314 -0.01511
+ hand
+
+
+ 0.02879 -0.09437 -0.02823
+ hand
+
+
+ 0.0287 -0.08524 -0.04295
+ hand
+
+
+ 0.02834 -0.07785 -0.05501
+ hand
+
+
+
+
+
+
+
+
+ Extensor_ellipse
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Secondpm_ext
+ hybrid
+ 7 8
+
+
+ Secondmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 47.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.01412 -0.09706 0.02952
+ ulna
+
+
+ 0.00124 -0.13668 0.0227
+ radius
+
+
+ 0.02702 -0.21872 0.03828
+ radius
+
+
+ 0.03382 -0.22754 0.04607
+ radius
+
+
+ 0.04234 -0.23771 0.04173
+ radius
+
+
+ 0.02428 0.00014 0.00608
+ hand
+
+
+ 0.02338 -0.00917 -0.00039
+ hand
+
+
+ 0.02905 -0.01427 -0.00489
+ hand
+
+
+ 0.04414 -0.03417 -0.01814
+ hand
+
+
+ 0.04867 -0.04646 -0.02487
+ hand
+
+
+ 0.04751 -0.0701 -0.03774
+ hand
+
+
+ 0.04011 -0.07565 -0.04283
+ hand
+
+
+
+
+
+
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 88.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01924 -0.14695 0.02114
+ radius
+
+
+ 0.02276 -0.15857 0.02665
+ radius
+
+
+ 0.03831 -0.19722 0.03834
+ radius
+
+
+ 0.05235 -0.23611 0.02699
+ radius
+
+
+ 0.03123 0.00256 -0.00327
+ hand
+
+
+ 0.02972 -0.00794 -0.01436
+ hand
+
+
+ 0.04422 -0.033 -0.02422
+ hand
+
+
+ 0.04528 -0.04785 -0.03186
+ hand
+
+
+
+
+
+
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 46
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00971 -0.09458 0.01769
+ radius
+
+
+ 0.01658 -0.13525 0.01915
+ radius
+
+
+ 0.01869 -0.17932 0.01988
+ radius
+
+
+ 0.038 -0.23171 0.0158
+ radius
+
+
+ 0.01869 0.00882 -0.01547
+ hand
+
+
+ -1.22173 0 1.22173
+ 0.01869 0.01869 0.01549
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ 0.00882 0.00882 -0.00078
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ -0.01547 -0.01547 -0.02087
+
+
+ flexion
+
+
+ 0.01244 -0.02207 -0.02089
+ hand
+
+
+ 0.01641 -0.02621 -0.02221
+ hand
+
+
+ 0.02457 -0.03294 -0.02237
+ hand
+
+
+ 0.02827 -0.05482 -0.03055
+ hand
+
+
+ 0.03511 -0.06519 -0.03749
+ hand
+
+
+ 0.03533 -0.07656 -0.04118
+ hand
+
+
+
+
+
+
+
+
+ FPL
+ hybrid
+ -1 -1
+
+
+ IPthumb
+ hybrid
+ 10 11
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 201
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01154 -0.09477 0.01681
+ radius
+
+
+ 0.0303 -0.1397 0.03507
+ radius
+
+
+ 0.03993 -0.16072 0.034
+ radius
+
+
+ 0.04397 -0.17845 0.03134
+ radius
+
+
+ 0.05505 -0.23084 0.02368
+ radius
+
+
+ 0.03385 0.00634 -0.00745
+ hand
+
+
+ -1.22173 0 1.22173
+ 0.03385 0.03385 0.03135
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ 0.00634 0.00634 0.00534
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ -0.00745 -0.00745 -0.01245
+
+
+ flexion
+
+
+ 0.02587 0.00205 -0.0165
+ hand
+
+
+ 0.02878 -0.00674 -0.0187
+ hand
+
+
+ 0.03076 -0.01583 -0.01885
+ hand
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 116.7
+
+
+
+
+
+
+
+
+
+ hand
+
+ 0.0266161 -0.0757448 -0.0576116
+
+ false
+
+
+
+
+
+
+
+
+
+
+
diff --git a/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/opensim.log b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/opensim.log
new file mode 100644
index 0000000000..ee27d99b4e
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExamplePerreault2001Experiment/opensim.log
@@ -0,0 +1,742 @@
+[2024-01-18 08:29:30.166] [info] Updating Model file from 30000 to latest format...
+[2024-01-18 08:29:30.208] [info] Loaded model MoBL_2016_Ideal_Muscles from file C:\Users\nathan.pickle\Documents\Source\OpenSim4\opensim-core-source\OpenSim\Examples\TaskSpace\ExamplePerreault2001Experiment\mobl_2016_ideal_muscles.osim
+[2024-01-18 08:29:30.210] [warning] Couldn't find file 'thorax.vtp'.
+[2024-01-18 08:29:30.211] [warning] Couldn't find file 'clavicle.vtp'.
+[2024-01-18 08:29:30.211] [warning] Couldn't find file 'scapula.vtp'.
+[2024-01-18 08:29:30.233] [warning] Couldn't find file 'lunate.vtp'.
+[2024-01-18 08:29:30.233] [warning] Couldn't find file 'sdfastSCAPHOIDw.vtp'.
+[2024-01-18 08:29:30.233] [warning] Couldn't find file 'sdfastPISIFORMw.vtp'.
+[2024-01-18 08:29:30.233] [warning] Couldn't find file 'sdfastTRIQUETRALw.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_5mc.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_4mc.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_3mc.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_2mc.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_trapezium.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_trapezoid.vtp'.
+[2024-01-18 08:29:30.234] [warning] Couldn't find file 'sdfast_1seg_hand_fr_c_hamate.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'capitate.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_2proxph.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_2midph.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_2distph.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_3proxph.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_3midph.vtp'.
+[2024-01-18 08:29:30.235] [warning] Couldn't find file 'hand_3distph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_4proxph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_4midph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_4distph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_5proxph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_5midph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_5distph.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_thumbprox.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_thumbdist.vtp'.
+[2024-01-18 08:29:30.236] [warning] Couldn't find file 'hand_1mc.vtp'.
+[2024-01-18 08:29:30.236] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.236] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.236] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.237] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-18 08:29:30.238] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-18 08:29:50.119] [warning] Visualizer couldn't open thorax.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\thorax.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\thorax.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.120] [warning] Visualizer couldn't open clavicle.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\clavicle.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\clavicle.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.121] [warning] Visualizer couldn't open scapula.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\scapula.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\scapula.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.140] [warning] Visualizer couldn't open lunate.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\lunate.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\lunate.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.140] [warning] Visualizer couldn't open sdfastSCAPHOIDw.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastSCAPHOIDw.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastSCAPHOIDw.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.140] [warning] Visualizer couldn't open sdfastPISIFORMw.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastPISIFORMw.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastPISIFORMw.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.140] [warning] Visualizer couldn't open sdfastTRIQUETRALw.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastTRIQUETRALw.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfastTRIQUETRALw.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_5mc.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_5mc.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_5mc.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_4mc.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_4mc.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_4mc.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_3mc.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_3mc.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_3mc.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_2mc.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_2mc.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_2mc.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_trapezium.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_trapezium.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_trapezium.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_trapezoid.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_trapezoid.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_trapezoid.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open sdfast_1seg_hand_fr_c_hamate.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_hamate.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\sdfast_1seg_hand_fr_c_hamate.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open capitate.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\capitate.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\capitate.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_2proxph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2proxph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2proxph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_2midph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2midph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2midph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_2distph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2distph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_2distph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_3proxph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3proxph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3proxph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_3midph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3midph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3midph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_3distph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3distph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_3distph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_4proxph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4proxph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4proxph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.141] [warning] Visualizer couldn't open hand_4midph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4midph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4midph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_4distph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4distph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_4distph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_5proxph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5proxph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5proxph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_5midph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5midph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5midph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_5distph.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5distph.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_5distph.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_thumbprox.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_thumbprox.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_thumbprox.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_thumbdist.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_thumbdist.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_thumbdist.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:29:50.142] [warning] Visualizer couldn't open hand_1mc.vtp because: SimTK Exception thrown at PolygonalMesh.cpp:411:
+ Error detected by Simbody method PolygonalMesh::loadVtpFile(): Attempt to load a VTK PolyData (.vtp) file from file name 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_1mc.vtp' failed with message:
+ SimTK Exception thrown at Xml.cpp:108:
+ Error detected by Simbody method Xml::readFromFile(): Failed to load the Xml file 'C:\OpenSim 4.5-2023-07-13-4cc8683\opensim\..\\Geometry\hand_1mc.vtp' with error 'Failed to open file (line=0, col=0)'.
+ (Required condition 'loadOK' was not met.)
+
+ (Required condition '!"failed"' was not met.)
+
+[2024-01-18 08:30:12.674] [warning] Running tool MoBL_2016_Ideal_Muscles...
+[2024-01-18 08:30:12.674] [info] No external loads will be applied (external loads file not specified).
+[2024-01-18 08:30:12.685] [cout] [info] MODEL: MoBL_2016_Ideal_Muscles
+
+numStates = 40
+numCoordinates = 20
+numSpeeds = 20
+numActuators = 47
+numBodies = 11
+numConstraints = 13
+numProbes = 0
+
+ANALYSES (total: 2)
+analysis[0] = Un-named analysis.
+analysis[1] = Un-named analysis.
+
+BODIES (total: 11)
+body[0] = clavicle. mass: 0.156
+ moments of inertia: ~[0.00024259,0.00025526,4.442e-05]
+ products of inertia: ~[-1.898e-05,-6.994e-05,5.371e-05]
+body[1] = clavphant. mass: 0.0001
+ moments of inertia: ~[1,1,1]
+ products of inertia: ~[0,0,0]
+body[2] = scapula. mass: 0.70396
+ moments of inertia: ~[0.0012429,0.0011504,0.0013651]
+ products of inertia: ~[0.0004494,0.00040922,0.0002411]
+body[3] = scapphant. mass: 0.0001
+ moments of inertia: ~[1,1,1]
+ products of inertia: ~[0,0,0]
+body[4] = humphant. mass: 0.0001
+ moments of inertia: ~[1,1,1]
+ products of inertia: ~[0,0,0]
+body[5] = humphant1. mass: 0.0001
+ moments of inertia: ~[1,1,1]
+ products of inertia: ~[0,0,0]
+body[6] = humerus. mass: 1.99757
+ moments of inertia: ~[0.0122776,0.00255133,0.0125789]
+ products of inertia: ~[-0.00034741,-0.0002325,0.0012293]
+body[7] = ulna. mass: 1.1053
+ moments of inertia: ~[0.00541309,0.00115318,0.00494361]
+ products of inertia: ~[0.00031686,-7.615e-05,0.00109169]
+body[8] = radius. mass: 0.23359
+ moments of inertia: ~[0.00043855,8.859e-05,0.00040258]
+ products of inertia: ~[3.014e-05,-4.24e-06,6.418e-05]
+body[9] = proximal_row. mass: 0.0001
+ moments of inertia: ~[1e-05,1e-05,1e-05]
+ products of inertia: ~[0,0,0]
+body[10] = hand. mass: 0.5819
+ moments of inertia: ~[0.00011,6e-05,0.00015]
+ products of inertia: ~[9e-07,-2e-07,1.2e-05]
+
+JOINTS (total: 11)
+joint[0] = sternoclavicular. parent: ground_offset, child: clavicle_offset
+joint[1] = unrotscap. parent: clavicle_offset, child: clavphant_offset
+joint[2] = acromioclavicular. parent: clavphant_offset, child: scapula_offset
+joint[3] = unrothum. parent: scapula_offset, child: scapphant_offset
+joint[4] = shoulder0. parent: scapphant_offset, child: humphant_offset
+joint[5] = shoulder1. parent: humphant_offset, child: humphant1_offset
+joint[6] = shoulder2. parent: humphant1_offset, child: humerus_offset
+joint[7] = elbow. parent: humerus_offset, child: ulna_offset
+joint[8] = radioulnar. parent: ulna_offset, child: radius_offset
+joint[9] = radiocarpal. parent: radius_offset, child: proximal_row_offset
+joint[10] = wrist_hand. parent: proximal_row_offset, child: hand_offset
+
+ACTUATORS (total: 47)
+actuator[0] = DELT1
+actuator[1] = DELT3
+actuator[2] = SUPSP
+actuator[3] = INFSP
+actuator[4] = SUBSC
+actuator[5] = TMIN
+actuator[6] = TMAJ
+actuator[7] = PECM1
+actuator[8] = PECM2
+actuator[9] = PECM3
+actuator[10] = LAT1
+actuator[11] = LAT2
+actuator[12] = LAT3
+actuator[13] = CORB
+actuator[14] = TRIlong
+actuator[15] = TRIlat
+actuator[16] = TRImed
+actuator[17] = ANC
+actuator[18] = SUP
+actuator[19] = BRA
+actuator[20] = BRD
+actuator[21] = ECRL
+actuator[22] = ECRB
+actuator[23] = ECU
+actuator[24] = FCR
+actuator[25] = FCU
+actuator[26] = PL
+actuator[27] = PT
+actuator[28] = PQ
+actuator[29] = FDSL
+actuator[30] = FDSR
+actuator[31] = FDSM
+actuator[32] = FDSI
+actuator[33] = FDPL
+actuator[34] = FDPR
+actuator[35] = FDPM
+actuator[36] = FDPI
+actuator[37] = EDCL
+actuator[38] = EDCR
+actuator[39] = EDCM
+actuator[40] = EDCI
+actuator[41] = EDM
+actuator[42] = EIP
+actuator[43] = EPL
+actuator[44] = EPB
+actuator[45] = FPL
+actuator[46] = APL
+
+STATES (total: 40)
+y[0] = /jointset/sternoclavicular/sternoclavicular_r2/value
+y[1] = /jointset/sternoclavicular/sternoclavicular_r2/speed
+y[2] = /jointset/sternoclavicular/sternoclavicular_r3/value
+y[3] = /jointset/sternoclavicular/sternoclavicular_r3/speed
+y[4] = /jointset/unrotscap/unrotscap_r3/value
+y[5] = /jointset/unrotscap/unrotscap_r3/speed
+y[6] = /jointset/unrotscap/unrotscap_r2/value
+y[7] = /jointset/unrotscap/unrotscap_r2/speed
+y[8] = /jointset/acromioclavicular/acromioclavicular_r2/value
+y[9] = /jointset/acromioclavicular/acromioclavicular_r2/speed
+y[10] = /jointset/acromioclavicular/acromioclavicular_r3/value
+y[11] = /jointset/acromioclavicular/acromioclavicular_r3/speed
+y[12] = /jointset/acromioclavicular/acromioclavicular_r1/value
+y[13] = /jointset/acromioclavicular/acromioclavicular_r1/speed
+y[14] = /jointset/unrothum/unrothum_r1/value
+y[15] = /jointset/unrothum/unrothum_r1/speed
+y[16] = /jointset/unrothum/unrothum_r3/value
+y[17] = /jointset/unrothum/unrothum_r3/speed
+y[18] = /jointset/unrothum/unrothum_r2/value
+y[19] = /jointset/unrothum/unrothum_r2/speed
+y[20] = /jointset/shoulder0/elv_angle/value
+y[21] = /jointset/shoulder0/elv_angle/speed
+y[22] = /jointset/shoulder1/shoulder_elv/value
+y[23] = /jointset/shoulder1/shoulder_elv/speed
+y[24] = /jointset/shoulder1/shoulder1_r2/value
+y[25] = /jointset/shoulder1/shoulder1_r2/speed
+y[26] = /jointset/shoulder2/shoulder_rot/value
+y[27] = /jointset/shoulder2/shoulder_rot/speed
+y[28] = /jointset/elbow/elbow_flexion/value
+y[29] = /jointset/elbow/elbow_flexion/speed
+y[30] = /jointset/radioulnar/pro_sup/value
+y[31] = /jointset/radioulnar/pro_sup/speed
+y[32] = /jointset/radiocarpal/deviation/value
+y[33] = /jointset/radiocarpal/deviation/speed
+y[34] = /jointset/radiocarpal/flexion/value
+y[35] = /jointset/radiocarpal/flexion/speed
+y[36] = /jointset/wrist_hand/wrist_hand_r1/value
+y[37] = /jointset/wrist_hand/wrist_hand_r1/speed
+y[38] = /jointset/wrist_hand/wrist_hand_r3/value
+y[39] = /jointset/wrist_hand/wrist_hand_r3/speed
+
+[2024-01-18 08:30:12.685] [info] Integrating from 0.0 to 5.0.
+[2024-01-19 14:29:14.364] [info] Updating Model file from 30000 to latest format...
+[2024-01-19 14:29:14.442] [info] Loaded model MoBL_2016_Ideal_Muscles from file C:\Users\nathan.pickle\Documents\Source\OpenSim4\opensim-core-source\OpenSim\Examples\TaskSpace\ExamplePerreault2001Experiment\mobl_2016_ideal_muscles.osim
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.448] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.449] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:14.450] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.581] [info] Updating Model file from 30000 to latest format...
+[2024-01-19 14:29:45.616] [info] Loaded model MoBL_2016_Ideal_Muscles from file C:\Users\nathan.pickle\Documents\Source\StanevTaskSpace\data\mobl\mobl_2016_ideal_muscles.osim
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.618] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.619] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:29:45.620] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.098] [info] Updating Model file from 30000 to latest format...
+[2024-01-19 14:31:32.126] [info] Loaded model MoBL_2016_Ideal_Muscles from file C:\Users\nathan.pickle\Documents\Source\OpenSim4\opensim-core-build\RelWithDebInfo\mobl_2016_ideal_muscles.osim
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'default'. The duplicate is being renamed to 'default_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.129] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_2'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_0'.
+[2024-01-19 14:31:32.130] [warning] GeometryPath 'geometrypath' has subcomponents with duplicate name 'pathwrap'. The duplicate is being renamed to 'pathwrap_1'.
diff --git a/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/CMakeLists.txt
new file mode 100644
index 0000000000..546387a58f
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/CMakeLists.txt
@@ -0,0 +1,8 @@
+
+set(EXAMPLE_BALANCE2D_FILES
+ gait2d.osim
+ )
+
+OpenSimAddExampleCXX(NAME ExampleStandingBalance2D SUBDIR TaskSpace
+ EXECUTABLES ExampleStandingBalance2D
+ RESOURCES "${EXAMPLE_BALANCE2D_FILES}")
diff --git a/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/ExampleStandingBalance2D.cpp b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/ExampleStandingBalance2D.cpp
new file mode 100644
index 0000000000..aaab2069b0
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/ExampleStandingBalance2D.cpp
@@ -0,0 +1,294 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim TaskSpace: ExampleStandingBalance2D.cpp *
+ * -------------------------------------------------------------------------- *
+ * Copyright (c) 2024 CFD Resarch Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Ryan Middle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+/**
+ * @file ExampleStandingBalance2D.cpp
+ *
+ * \brief
+ *
+ * @authors Nathan Pickle, Aravind Sundararajan, Garrett Tuer, Ryan Middle
+ *
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+#include "OpenSim/Moco/MocoUtilities.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+#define USE_VISUALIZER 1
+
+void balanceSimulation() {
+ const string example = "ExampleStandingBalance2D";
+
+ ModelVisualizer::addDirToGeometrySearchPaths(OPENSIM_GEOMETRY_DIR);
+
+ // load model
+ Model model("gait2d.osim");
+
+ // // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ auto kinematics = new StatesReporter(&model);
+ kinematics->setInDegrees(false);
+ model.addAnalysis(kinematics);
+
+ // define the controller
+ auto controller = new TaskSpaceTorqueController();
+ // Specify the constraint model to use
+ controller->set_ConstraintModel(SupportModel());
+
+ model.addController(controller);
+
+ // Specify unactuated coordinates in the model
+ Array excluded_coords;
+ excluded_coords.append("rz");
+ excluded_coords.append("tx");
+ excluded_coords.append("ty");
+ controller->set_excluded_coords(excluded_coords);
+
+ // build and initialize model
+ auto& state = model.initSystem();
+
+ // initial configuration
+ auto& torso = model.updBodySet().get("torso");
+ auto initialOrientation_torso = torso.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ auto initialPosition_torso = torso.findStationLocationInGround(state, torso.getMassCenter());
+
+ auto& pelvis = model.updBodySet().get("pelvis");
+ auto initialOrientation_pelvis = pelvis.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ auto initialPosition_pelvis = pelvis.findStationLocationInGround(state, pelvis.getMassCenter());
+
+ auto& hand_r = model.updBodySet().get("hand_r");
+ auto initialOrientation_hand_r = hand_r.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ auto initialPosition_hand_r = hand_r.findStationLocationInGround(state, hand_r.getMassCenter());
+
+ auto& hand_l = model.updBodySet().get("hand_l");
+ auto initialOrientation_hand_l = hand_l.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ auto initialPosition_hand_l = hand_l.findStationLocationInGround(state, hand_l.getMassCenter());
+
+ Array weights(1.0, 3);
+
+ //========================
+ // TORSO
+ //========================
+ // Torso orientation
+ auto torso_orientation_task = new OrientationTask();
+ torso_orientation_task->setName("torso_orientation_task");
+ torso_orientation_task->set_priority(0);
+ torso_orientation_task->set_kp(Array(100, 3));
+ torso_orientation_task->set_kv(Array(20, 3));
+ weights[0] = 0.0;
+ weights[1] = 0.0;
+ weights[2] = 1;
+ torso_orientation_task->set_weight(weights);
+ auto tx_desired_com_2 = Constant(initialOrientation_torso[0]);
+ auto ty_desired_com_2 = Constant(initialOrientation_torso[1]);
+ auto tz_desired_com_2 = Constant(initialOrientation_torso[2]);
+ torso_orientation_task->set_position_functions(0, tx_desired_com_2);
+ torso_orientation_task->set_position_functions(1, ty_desired_com_2);
+ torso_orientation_task->set_position_functions(2, tz_desired_com_2);
+ torso_orientation_task->set_wrt_body("torso");
+ torso_orientation_task->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(torso_orientation_task);
+
+ //========================
+ // PELVIS
+ //========================
+
+ // Pelvis forward progression tracking
+ auto pelvis_position_task = new StationTask();
+ pelvis_position_task->setName("pelvis_position");
+ pelvis_position_task->set_priority(0);
+ pelvis_position_task->set_kp(Array(100, 3));
+ pelvis_position_task->set_kv(Array(20, 3));
+ weights[0] = 1.0;
+ weights[1] = 1.0;
+ weights[2] = 0.0;
+ pelvis_position_task->set_weight(weights);
+ pelvis_position_task->set_point(pelvis.getMassCenter());
+ auto tx_desired_pelvis = Constant(initialPosition_pelvis[0]);
+ auto ty_desired_pelvis = Constant(initialPosition_pelvis[1]);
+ auto tz_desired_pelvis = Constant(0);
+ pelvis_position_task->set_position_functions(0, tx_desired_pelvis);
+ pelvis_position_task->set_position_functions(1, ty_desired_pelvis);
+ pelvis_position_task->set_position_functions(2, tz_desired_pelvis);
+ pelvis_position_task->set_wrt_body("pelvis");
+ pelvis_position_task->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(pelvis_position_task);
+
+ // Pelvis orientation
+ auto pelvis_orientation_task = new OrientationTask();
+ pelvis_orientation_task->setName("pelvis_orientation_task");
+ pelvis_orientation_task->set_priority(0);
+ pelvis_orientation_task->set_kp(Array(100, 3));
+ pelvis_orientation_task->set_kv(Array(20, 3));
+ weights[0] = 0.0;
+ weights[1] = 0.0;
+ weights[2] = 1.0;
+ pelvis_orientation_task->set_weight(weights);
+ auto rx_desired_pelvis = Constant(initialOrientation_pelvis[0]);
+ auto ry_desired_pelvis = Constant(initialOrientation_pelvis[1]);
+ auto rz_desired_pelvis = Constant(initialOrientation_pelvis[2]);
+ pelvis_orientation_task->set_position_functions(0, rx_desired_pelvis);
+ pelvis_orientation_task->set_position_functions(1, ry_desired_pelvis);
+ pelvis_orientation_task->set_position_functions(2, rz_desired_pelvis);
+ pelvis_orientation_task->set_wrt_body("pelvis");
+ pelvis_orientation_task->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(pelvis_orientation_task);
+
+ //========================
+ // HANDS
+ //========================
+
+ // RIGHT HAND
+ auto hand_position_r = new StationTask();
+ hand_position_r->setName("hand_position_r");
+ hand_position_r->set_priority(0);
+ hand_position_r->set_kp(Array(100,3));
+ hand_position_r->set_kv(Array(20,3));
+ weights[0] = 1.0;
+ weights[1] = 1.0;
+ weights[2] = 0.0;
+ hand_position_r->set_weight(weights);
+ hand_position_r->set_point(hand_r.getMassCenter());
+ auto tx_desired_hand_r = Constant(initialPosition_hand_r[0]);
+ auto ty_desired_hand_r = Constant(initialPosition_hand_r[1]);
+ auto tz_desired_hand_r = Constant(initialPosition_hand_r[2]);
+ hand_position_r->set_position_functions(0, tx_desired_hand_r);
+ hand_position_r->set_position_functions(1, ty_desired_hand_r);
+ hand_position_r->set_position_functions(2, tz_desired_hand_r);
+ hand_position_r->set_wrt_body("hand_r");
+ hand_position_r->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_position_r);
+
+ auto hand_orientation_r = new OrientationTask();
+ hand_orientation_r->setName("hand_orientation_r");
+ hand_orientation_r->set_priority(0);
+ hand_orientation_r->set_kp(Array(100,3));
+ hand_orientation_r->set_kv(Array(20,3));
+ weights[0] = 1.0;
+ weights[1] = 1.0;
+ weights[2] = 0.0;
+ hand_orientation_r->set_weight(weights);
+ auto rx_desired_hand_r = Constant(initialOrientation_hand_r[0]);
+ auto ry_desired_hand_r = Constant(initialOrientation_hand_r[1]);
+ auto rz_desired_hand_r = Constant(initialOrientation_hand_r[2]);
+ hand_orientation_r->set_position_functions(0, rx_desired_hand_r);
+ hand_orientation_r->set_position_functions(1, ry_desired_hand_r);
+ hand_orientation_r->set_position_functions(2, rz_desired_hand_r);
+ hand_orientation_r->set_wrt_body("hand_r");
+ hand_orientation_r->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_orientation_r);
+
+ // LEFT HAND
+ auto hand_position_l = new StationTask();
+ hand_position_l->setName("hand_position_l");
+ hand_position_l->set_priority(0);
+ hand_position_l->set_kp(Array(100,3));
+ hand_position_l->set_kv(Array(20,3));
+ weights[0] = 1.0;
+ weights[1] = 1.0;
+ weights[2] = 0.0;
+ hand_position_l->set_weight(weights);
+ hand_position_l->set_point(hand_l.getMassCenter());
+ auto tx_desired_hand_l = Constant(initialPosition_hand_l[0]);
+ auto ty_desired_hand_l = Constant(initialPosition_hand_l[1]);
+ auto tz_desired_hand_l = Constant(initialPosition_hand_l[2]);
+ hand_position_l->set_position_functions(0, tx_desired_hand_l);
+ hand_position_l->set_position_functions(1, ty_desired_hand_l);
+ hand_position_l->set_position_functions(2, tz_desired_hand_l);
+ hand_position_l->set_wrt_body("hand_l");
+ hand_position_l->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_position_l);
+
+ auto hand_orientation_l = new OrientationTask();
+ hand_orientation_l->setName("hand_orientation_l");
+ hand_orientation_l->set_priority(0);
+ hand_orientation_l->set_kp(Array(100,3));
+ hand_orientation_l->set_kv(Array(20,3));
+ weights[0] = 1.0;
+ weights[1] = 1.0;
+ weights[2] = 0.0;
+ hand_orientation_l->set_weight(weights);
+ auto rx_desired_hand_l = Constant(initialOrientation_hand_l[0]);
+ auto ry_desired_hand_l = Constant(initialOrientation_hand_l[1]);
+ auto rz_desired_hand_l = Constant(initialOrientation_hand_l[2]);
+ hand_orientation_l->set_position_functions(0, rx_desired_hand_l);
+ hand_orientation_l->set_position_functions(1, ry_desired_hand_l);
+ hand_orientation_l->set_position_functions(2, rz_desired_hand_l);
+ hand_orientation_l->set_wrt_body("hand_l");
+ hand_orientation_l->set_express_body("ground");
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_orientation_l);
+
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+
+#if USE_VISUALIZER == 1
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(Visualizer::BackgroundType::SolidColor);
+ model.updVisualizer().updSimbodyVisualizer().setDesiredFrameRate(200);
+ model.updVisualizer().updSimbodyVisualizer().setShowFrameRate(true);
+ model.updVisualizer().updSimbodyVisualizer().setShowSimTime(true);
+ model.updVisualizer().updSimbodyVisualizer().setRealTimeScale(0.5);
+ model.updMatterSubsystem().setShowDefaultGeometry(false);
+#endif
+
+ state.setTime(0.0);
+ Manager manager(model);
+ manager.initialize(state);
+ double end_time = 2;
+ log_info("\nIntegrating from {} to {}", 0.0, end_time);
+ state = manager.integrate(end_time);
+ model.setUseVisualizer(false);
+
+ // export results
+ IO::makeDir("./results");
+ controller->printResults(example, "./results");
+ bodyKinematics->printResults(example, "./results");
+ kinematics->printResults(example, "./results");
+ auto tab = manager.getStatesTable();
+ StatesTrajectory ST = StatesTrajectory::createFromStatesTable(model, tab);
+ std::vector contact_r;
+ std::vector contact_l;
+ contact_r.push_back("/forceset/contactHeel_r");
+ contact_r.push_back("/forceset/contactToes_r");
+ contact_l.push_back("/forceset/contactHeel_l");
+ contact_l.push_back("/forceset/contactToes_l");
+ auto externalForcesTableFlat = createExternalLoadsTableForGait(model, ST, contact_r, contact_l);
+ STOFileAdapter::write(externalForcesTableFlat,
+ "./results/"+example+"_grf.sto");
+ log_info("Done!");
+}
+
+int main(int argc, char* argv[]) {
+ Logger::setLevel(Logger::Level::Info);
+ try {
+ balanceSimulation();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ getchar();
+ return -1;
+ }
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/gait2d.osim b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/gait2d.osim
new file mode 100644
index 0000000000..f3b22343af
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleStandingBalance2D/gait2d.osim
@@ -0,0 +1,2508 @@
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ r_pelvis.vtp
+
+
+
+ ..
+
+ l_pelvis.vtp
+
+
+
+ ..
+
+ sacrum.vtp
+
+
+
+ 5
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ femur_r.vtp
+
+
+
+ 3
+
+ 0 0 0
+
+ 0.10000000149011612 1 0.10000000149011612 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ tibia_r.vtp
+
+
+
+ 2
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ femur_l.vtp
+
+
+
+ 3
+
+ 0 0 0
+
+ 0.10000000149011612 1 0.10000000149011612 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ tibia_l.vtp
+
+
+
+ 2
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ hat_spine.vtp
+
+
+
+ ..
+
+ hat_skull.vtp
+
+
+
+ ..
+
+ hat_ribs_scap.vtp
+
+
+
+ ..
+
+ hat_jaw.vtp
+
+
+
+ 20
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ r_foot.vtp
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ l_foot.vtp
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ bofoot.vtp
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+
+
+ ..
+
+ l_bofoot.vtp
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ humerus_rv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ulna_rv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ radius_rv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ pisiform_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ lunate_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ scaphoid_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ triquetrum_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ hamate_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ capitate_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ trapezoid_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ trapezium_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal2_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_proximal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_medial_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_distal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal3_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_proximal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_medial_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_distal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal4_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_proximal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_medial_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_distal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal5_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_proximal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_medial_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_distal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal1_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ thumb_proximal_rvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ thumb_distal_rvs.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ humerus_lv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ulna_lv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 1 1 1
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ radius_lv.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+
+ true
+
+
+
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ pisiform_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ lunate_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ scaphoid_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ triquetrum_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ hamate_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ capitate_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ trapezoid_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ trapezium_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal2_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_proximal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_medial_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ index_distal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal3_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_proximal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_medial_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ middle_distal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal4_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_proximal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_medial_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ ring_distal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal5_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_proximal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_medial_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ little_distal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ metacarpal1_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ thumb_proximal_lvs.vtp
+
+
+
+ ..
+
+ 0.84999999999999998 0.84999999999999998 0.84999999999999998
+
+
+
+ true
+
+ 1
+
+ 1 1 1
+
+
+ thumb_distal_lvs.vtp
+
+
+
+
+
+
+
+
+ 1
+
+ 0 0 0
+
+ 1 1 1 0 0 0
+
+
+
+
+
+
+
+
+
+ ground_offset
+
+ foot_offset
+
+
+
+
+ -0.27054854706742482
+
+ false
+
+
+
+ -0.25706963798984245
+
+
+
+ 0.88214967400257416
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /ground
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/pelvis
+
+
+
+
+
+ ground_offset
+
+ femur_offset
+
+
+
+
+ 0.58091182222357185
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/pelvis
+
+ -0.07029300183057785 -0.069026000797748566 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/femur_l
+
+ 0 0 0.10000000149011612
+
+
+
+
+
+ femur_offset
+
+ tibia_offset
+
+
+
+
+ -0.60589104982983155
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/femur_l
+
+ 0.0053650001063942909 -0.4114220142364502 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/tibia_l
+
+ 0.00038799998583272099 0.0025259999092668295 0
+
+
+
+
+
+ ground_offset
+
+ femur_offset
+
+
+
+
+ 0.58091414242066552
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/pelvis
+
+ -0.070293068885803223 -0.069026283919811249 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/femur_r
+
+ 0 0 -0.10000000149011612
+
+ 0 0 0
+
+
+
+
+
+ femur_offset
+
+ tibia_offset
+
+
+
+
+ -0.6058974500185268
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/femur_r
+
+ 0.0053651370990195346 -0.41142204938995519 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/tibia_r
+
+ 0.00038833136204630136 0.002526434138417244 0
+
+ 0 0 0
+
+
+
+
+
+ ground_offset
+
+ torso_offset
+
+
+
+
+ 0.16806132931620432
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/pelvis
+
+ -0.10288058597695482 0.08121604692143336 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/torso
+
+ 0 0 0
+
+
+
+
+
+ tibia_r_offset
+
+ foot_r_offset
+
+
+
+
+ 0.30446376282544552
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/tibia_r
+
+ 0.00043203607001363054 -0.40722375734244309 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/calcn_r
+
+ 0.03000001423060894 0.039999999105930328 0
+
+
+
+
+
+ tibia_l_offset
+
+ foot_l_offset
+
+
+
+
+ 0.30446105691727976
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/tibia_l
+
+ 0.00043200000072829425 -0.40722399950027466 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/calcn_l
+
+ 0.029999999329447746 0.039999999105930328 0
+
+
+
+
+
+ /bodyset/calcn_r
+
+ toes_r_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/calcn_r
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/toes_r
+
+ -0.18000000715255737 0 0
+
+
+
+
+
+ foot_l_offset
+
+ toes_l_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/calcn_l
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/toes_l
+
+ -0.18000000715255737 0 0
+
+
+
+
+
+ torso_offset
+
+ humerus_r_offset
+
+
+
+
+ 0.084020150191007018
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/torso
+
+ 0.0031549999999999998 0.3715 0.17000000000000001
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/humerus_r
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ humerus_r_offset
+
+ ulna_r_offset
+
+
+
+
+ 0.34958944917446422
+
+ 0
+
+ 0 2.6179999999999999
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/humerus_r
+
+ 0.013143999999999999 -0.286273 -0.0095949999999999994
+
+ -0.0228627 0.228018 0.0051688999999999997
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/ulna_r
+
+ 0 0 0
+
+ -0.0228627 0.228018 0.0051688999999999997
+
+
+
+
+
+ ulna_r_offset
+
+ radius_r_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/ulna_r
+
+ -0.0067270000000000003 -0.013006999999999999 0.026082999999999999
+
+ -1.56884 0.056427999999999999 1.5361400000000001
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/radius_r
+
+ 0 0 0
+
+ -1.5688400268554688 0.056428000330924988 0
+
+
+
+
+
+ radius_r_offset
+
+ hand_r_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/radius_r
+
+ -0.0087969999999999993 -0.235841 0.013610000000000001
+
+ -1.5708 0 -1.5708
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/hand_r
+
+ 0 0 0
+
+ -1.5708 0 -1.5708
+
+
+
+
+
+ torso_offset
+
+ humerus_l_offset
+
+
+
+
+ 0.084020150191007018
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/torso
+
+ 0.0031549999999999998 0.3715 -0.17000000000000001
+
+ 0 0 0
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/humerus_l
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ humerus_l_offset
+
+ ulna_l_offset
+
+
+
+
+ 0.34958944917446422
+
+ 0
+
+ 0 2.6179999999999999
+
+ true
+
+ false
+
+
+
+ false
+
+
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/humerus_l
+
+ 0.013143999999999999 -0.286273 0.0095949999999999994
+
+ 0.0228627 -0.228018 0.0051688999999999997
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/ulna_l
+
+ 0 0 0
+
+ 0.0228627 -0.228018 0.0051688999999999997
+
+
+
+
+
+ ulna_l_offset
+
+ radius_l_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/ulna_l
+
+ -0.0067270000000000003 -0.013006999999999999 -0.026082999999999999
+
+ 1.56884 -0.056427999999999999 1.5361400000000001
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/radius_l
+
+ 0 0 0
+
+ 1.5688400268554688 -0.056428000330924988 0
+
+
+
+
+
+ radius_l_offset
+
+ hand_l_offset
+
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/radius_l
+
+ -0.0087969999999999993 -0.235841 -0.013610000000000001
+
+ 1.5708 0 1.5708
+
+
+
+
+
+ ..
+
+ 0.20000000000000001 0.20000000000000001 0.20000000000000001
+
+
+ /bodyset/hand_l
+
+ 0 0 0
+
+ 1.5708 0 1.5708
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ /contactgeometryset/contactSphere_Heel_l
+
+ /contactgeometryset/floor
+
+ 300000
+
+ 2
+
+ 1
+
+ 1
+
+ 1
+
+ 0.01
+
+ 0.01
+
+ 300
+
+ 75
+
+
+
+ /contactgeometryset/contactSphere_Heel_r
+
+ /contactgeometryset/floor
+
+ 300000
+
+ 2
+
+ 1
+
+ 1
+
+ 1
+
+ 0.01
+
+ 0.01
+
+ 300
+
+ 75
+
+
+
+ /contactgeometryset/contactSphere_Toes_l
+
+ /contactgeometryset/floor
+
+ 300000
+
+ 2
+
+ 1
+
+ 1
+
+ 1
+
+ 0.01
+
+ 0.01
+
+ 300
+
+ 75
+
+
+
+ /contactgeometryset/contactSphere_Toes_r
+
+ /contactgeometryset/floor
+
+ 300000
+
+ 2
+
+ 1
+
+ 1
+
+ 1
+
+ 0.01
+
+ 0.01
+
+ 300
+
+ 75
+
+
+
+
+
+
+
+
+
+ /ground
+
+ 0 0 -1.5707963705062866
+
+
+
+ /bodyset/calcn_l
+
+ 0 0 0
+
+ 0.0099999997764825821
+
+
+
+ /bodyset/calcn_r
+
+ 0 0 0
+
+ 0 0 0
+
+ 0.0099999997764825821
+
+
+
+ /bodyset/calcn_r
+
+ 0.20000000298023224 0 0
+
+ 0.0099999997764825821
+
+
+
+ /bodyset/calcn_l
+
+ 0.20000000298023224 0 0
+
+ 0.0099999997764825821
+
+
+
+
+
+
+
+
+
+ true
+
+ true
+
+ false
+
+
+
+
diff --git a/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/CMakeLists.txt
new file mode 100644
index 0000000000..dfc75e48bd
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/CMakeLists.txt
@@ -0,0 +1,5 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExampleTaskBasedControlSUBDIR TaskSpace
+ EXECUTABLES ExampleTaskBasedControl
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/ExampleTaskBasedControl.cpp b/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/ExampleTaskBasedControl.cpp
new file mode 100644
index 0000000000..ab7b67c278
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleTaskBasedControl/ExampleTaskBasedControl.cpp
@@ -0,0 +1,147 @@
+/**
+ * @file ExampleTaskBasedControl.cpp
+ *
+ * \brief An example of utilizing the task based projection in order to control
+ * a model in task space. In this example a block is created and a position task
+ * is assigned. The goal is prescribed using a PD tracking controller and a
+ * forward simulation is performed.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ */
+
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+Model constructModel(const std::string& name)
+{
+ // create model
+ Model model;
+ model.setName(name);
+ model.setUseVisualizer(true);
+
+ Vec3 halfLength(0.2, 0.2, 0.2);
+ auto block =
+ new OpenSim::Body("block", 1, Vec3(0), Inertia::brick(halfLength));
+ auto blockGeom = new OpenSim::Brick(halfLength);
+ block->attachGeometry(blockGeom);
+ model.addBody(block);
+ auto joint = new FreeJoint("joint", model.getGround(), Vec3(0), Vec3(0),
+ *block, Vec3(0), Vec3(0));
+ model.addJoint(joint);
+
+ // add coordinate console reporter
+ auto reporter = new ConsoleReporter();
+ reporter->setName("reporter");
+ reporter->set_report_time_interval(0.1);
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::TranslationX)
+ .getOutput("value"),
+ "X");
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::TranslationY)
+ .getOutput("value"),
+ "Y");
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::TranslationZ)
+ .getOutput("value"),
+ "Z");
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::Rotation1X)
+ .getOutput("value"),
+ "thetaX");
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::Rotation2Y)
+ .getOutput("value"),
+ "thetaY");
+ reporter->addToReport(joint->getCoordinate(FreeJoint::Coord::Rotation3Z)
+ .getOutput("value"),
+ "thetaZ");
+ model.addComponent(reporter);
+
+ return model;
+}
+
+void taskBasedControl() {
+ const string example = "ExampleTaskBasedControl";
+
+ auto model = constructModel(example);
+
+ // construct a torque controller and supply the control strategy
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(NoConstraintModel());
+ model.addController(controller);
+
+ // initial configuration
+ Vec3 initialPosition(0, 0.5, 0);
+
+ // Position tracking
+ auto station_task = new StationTask();
+ station_task->setName("block_position");
+ station_task->set_wrt_body("block");
+ auto x_desired = Sine(1.0, 2 * Pi, 0, initialPosition[0]);
+ auto y_desired = Constant(initialPosition[1]);
+ auto z_desired = Constant(initialPosition[2]);
+ station_task->set_position_functions(0, x_desired);
+ station_task->set_position_functions(1, y_desired);
+ station_task->set_position_functions(2, z_desired);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(station_task);
+
+ // Orientation tracking
+ auto orientation_task = new OrientationTask();
+ orientation_task->setName("block_orientation");
+ orientation_task->set_wrt_body("block");
+ auto ox_desired = Constant(0);
+ auto oy_desired = Constant(0);
+ auto oz_desired = Sine(0.2, 2*Pi, 0, 0);
+ orientation_task->set_position_functions(0, ox_desired);
+ orientation_task->set_position_functions(1, oy_desired);
+ orientation_task->set_position_functions(2, oz_desired);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(orientation_task);
+
+ // Build and initialize model. Note this must be done AFTER adding the
+ // tasks to ensure proper initialization.
+ auto& state = model.initSystem();
+
+ // Set the model pose to the initial configuration.
+ auto joint = FreeJoint::safeDownCast(&model.updJointSet().get("joint"));
+ joint->updCoordinate(FreeJoint::Coord::TranslationX)
+ .setValue(state, initialPosition[0]);
+ joint->updCoordinate(FreeJoint::Coord::TranslationY)
+ .setValue(state, initialPosition[1]);
+ joint->updCoordinate(FreeJoint::Coord::TranslationZ)
+ .setValue(state, initialPosition[2]);
+
+ // configure visualizer
+ if (model.hasVisualizer()) {
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(
+ Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(true);
+ }
+
+ // print the complete model
+ IO::makeDir("results");
+ model.print(IO::getCwd()+"/results/"+example+".osim");
+
+ // simulate
+ simulate(model, state, 2, true);
+
+ // export results
+ controller->printResults(example, IO::getCwd()+"/results");
+ auto reporter = model.getComponent("reporter");
+ reporter.print("results/" + example + "_Reporter.sto");
+}
+
+int main(int argc, char* argv[]) {
+ Logger::setLevel(Logger::Level::Info);
+ try {
+ taskBasedControl();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ return -1;
+ }
+ return 0;
+}
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleUpperLimb/CMakeLists.txt b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/CMakeLists.txt
new file mode 100644
index 0000000000..d724e612bc
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/CMakeLists.txt
@@ -0,0 +1,5 @@
+file(GLOB_RECURSE TEST_FILES RELATIVE "${CMAKE_CURRENT_SOURCE_DIR}" *.osim)
+
+OpenSimAddExampleCXX(NAME ExampleUpperLimb SUBDIR TaskSpace
+ EXECUTABLES ExampleUpperLimb
+ RESOURCES "${TEST_FILES}")
\ No newline at end of file
diff --git a/OpenSim/Examples/TaskSpace/ExampleUpperLimb/ExampleUpperLimb.cpp b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/ExampleUpperLimb.cpp
new file mode 100644
index 0000000000..f6f0738937
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/ExampleUpperLimb.cpp
@@ -0,0 +1,159 @@
+/**
+ * @file ExampleUpperLimb.cpp
+ *
+ * \brief Control of the MoBL 2016 upper limb model.
+ *
+ * @authors Dimitar Stanev, Nathan Pickle, Aravind Sundararajan
+ *
+ * @see [Publication]
+ */
+#include "OpenSim/Common/osimCommon.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Analyses/osimAnalyses.h"
+#include "OpenSim/Tools/osimTools.h"
+
+using namespace std;
+using namespace OpenSim;
+using namespace SimTK;
+
+#define USE_VISUALIZER 1
+
+Vec3 fromVectorToVec3(const Vector& v) { return Vec3(v[0], v[1], v[2]); }
+
+void predictiveSimulation() {
+ const string example = "ExampleUpperLimb";
+
+ const double kp = 100;
+ const double kv = 20;
+
+ ModelVisualizer::addDirToGeometrySearchPaths(OPENSIM_GEOMETRY_DIR);
+
+ // load model
+ Model model("mobl_2016_ideal_muscles.osim");
+
+ // body kinematics
+ auto bodyKinematics = new BodyKinematics(&model);
+ bodyKinematics->setInDegrees(false);
+ model.addAnalysis(bodyKinematics);
+
+ // construct a torque controller and supply the control strategy
+ // define the controller
+ TaskSpaceTorqueController* controller = new TaskSpaceTorqueController();
+ controller->set_ConstraintModel(AghiliModel());
+ controller->set_control_strategy("force");
+ model.addController(controller);
+
+ auto marker = model.getMarkerSet().get("end_effector");
+ // here we just have to find the body to which the marker is
+ // attached, but due to OpenSim's Frame it is more difficult now
+ auto markerFrame = marker.getParentFrameName();
+ auto handBodyName = markerFrame.substr(markerFrame.find("/", 1) + 1);
+
+ // build and initialize model
+ auto& state = model.initSystem();
+ model.realizePosition(state);
+
+ model.updCoordinateSet()
+ .get("elv_angle")
+ .setValue(state, convertDegreesToRadians(50));
+ model.updCoordinateSet()
+ .get("shoulder_elv")
+ .setValue(state, convertDegreesToRadians(50));
+ model.updCoordinateSet()
+ .get("shoulder_rot")
+ .setValue(state, convertDegreesToRadians(-20));
+ model.updCoordinateSet()
+ .get("elbow_flexion")
+ .setValue(state, convertDegreesToRadians(95));
+ model.updCoordinateSet().get("pro_sup").setValue(
+ state, convertDegreesToRadians(75));
+ model.updCoordinateSet().get("flexion").setValue(
+ state, convertDegreesToRadians(0));
+
+ // hand initial configuration
+ auto& handBody = model.getBodySet().get(handBodyName);
+ Vec3 initialOrientation =
+ handBody.getRotationInGround(state).convertRotationToBodyFixedXYZ();
+ Vec3 initialPosition = handBody.getPositionInGround(state);
+
+ // Set up spatial tracking for the hand
+ auto hand_position = new StationTask();
+ hand_position->setName(handBodyName);
+ hand_position->set_kp(Array(kp, 3));
+ hand_position->set_kv(Array(kv, 3));
+ auto xpos_desired = Constant(initialPosition[0]);
+ // FOR REVIEW: The original code specified these positions as a function of
+ // two sinusoids multiplied together, which does not seem to be possible
+ // using built-in OpenSim Functions. Is this required functionality? If so,
+ // is there a way to implement it as a Function?
+ auto ypos_desired = Sine(0.1, Pi, 0, initialPosition[1]);
+ auto zpos_desired = Sine(0.1, 2 * Pi, 0, initialPosition[2]);
+ hand_position->set_position_functions(0, xpos_desired);
+ hand_position->set_position_functions(1, ypos_desired);
+ hand_position->set_position_functions(2, zpos_desired);
+ hand_position->set_wrt_body(handBodyName);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_position);
+
+ auto hand_orientation = new OrientationTask();
+ hand_orientation->setName(handBodyName);
+ hand_orientation->set_kp(Array(kp, 3));
+ hand_orientation->set_kv(Array(kv, 3));
+ auto xorient_desired = Constant(initialOrientation[0]);
+ auto yorient_desired = Constant(initialOrientation[1]);
+ auto zorient_desired = Constant(initialOrientation[2]);
+ hand_orientation->set_position_functions(0, xorient_desired);
+ hand_orientation->set_position_functions(1, yorient_desired);
+ hand_orientation->set_position_functions(2, zorient_desired);
+ hand_orientation->set_wrt_body(handBodyName);
+ controller->upd_TaskSpaceTaskSet().adoptAndAppend(hand_orientation);
+
+ // build and initialize model to initialize the tasks. also add a visualizer
+ model.setUseVisualizer(true);
+ state = model.initSystem();
+
+ // configure visualizer
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundColor(Vec3(0));
+ model.updVisualizer().updSimbodyVisualizer().setBackgroundType(
+ Visualizer::BackgroundType::SolidColor);
+ model.updMatterSubsystem().setShowDefaultGeometry(false);
+
+ // put the model back in initial position
+ model.realizePosition(state);
+ model.updCoordinateSet()
+ .get("elv_angle")
+ .setValue(state, convertDegreesToRadians(50));
+ model.updCoordinateSet()
+ .get("shoulder_elv")
+ .setValue(state, convertDegreesToRadians(50));
+ model.updCoordinateSet()
+ .get("shoulder_rot")
+ .setValue(state, convertDegreesToRadians(-20));
+ model.updCoordinateSet()
+ .get("elbow_flexion")
+ .setValue(state, convertDegreesToRadians(95));
+ model.updCoordinateSet().get("pro_sup").setValue(
+ state, convertDegreesToRadians(75));
+ model.updCoordinateSet().get("flexion").setValue(
+ state, convertDegreesToRadians(0));
+
+ // print the complete model
+ model.print("results/" + example + ".osim");
+
+ // simulate
+ simulate(model, state, 2.0, true);
+
+ // export results
+ controller->printResults(example, "results");
+ bodyKinematics->printResults(example, "results");
+}
+
+int main(int argc, char* argv[]) {
+ try {
+ predictiveSimulation();
+ } catch (exception& e) {
+ cout << typeid(e).name() << ": " << e.what() << endl;
+ // getchar();
+ return -1;
+ }
+ return 0;
+}
diff --git a/OpenSim/Examples/TaskSpace/ExampleUpperLimb/mobl_2016_ideal_muscles.osim b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/mobl_2016_ideal_muscles.osim
new file mode 100644
index 0000000000..0152ea2e21
--- /dev/null
+++ b/OpenSim/Examples/TaskSpace/ExampleUpperLimb/mobl_2016_ideal_muscles.osim
@@ -0,0 +1,9022 @@
+
+
+
+ Katherine R. Saul, Wendy M. Murray, Craig M. Goehler, Melissa Daly, Meghan E. Vidt, Dustin L. Crouch
+ Comp Meth Biomech Biomed Eng 2014
+ meters
+ N
+
+ 0 -9.80665 0
+
+
+
+
+ 0
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+
+
+
+
+ thorax.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.0434587 -0.331962 0.189892
+ -0.0386 -0.1273 0.0709
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0434587 -0.331962 0.189892 -0.0386 -0.1273 0.0709
+
+ false
+
+ 0
+
+ 0.1 0.135 0.08
+
+
+
+
+
+
+ 0.156
+ -0.011096 0.0063723 0.054168
+ 0.00024259
+ 0.00025526
+ 4.442e-005
+ -1.898e-005
+ -6.994e-005
+ 5.371e-005
+
+
+
+
+ ground
+
+ 0.006325 0.00693 0.025465
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.126710904892861
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0536688754806746
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ sternoclavicular_r2
+
+ 0.0153 0.9892987 -0.14509996
+
+
+
+ 1 0
+
+
+
+
+
+ sternoclavicular_r3
+
+ -0.99447254 0 -0.10499695
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ -0.10387335 0.14590438 0.98383039
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ clavicle.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ clavicle
+
+ -0.01433 0.02007 0.135535
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0536688754806746
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.126710904892861
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ unrotscap_r3
+
+ -0.99447254 0 -0.10499695
+
+
+
+ 1 0
+
+
+
+
+
+ unrotscap_r2
+
+ 0.0153 0.9892987 -0.14509996
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0.10387335 -0.14590438 -0.98383039
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.70396
+ -0.054694 -0.035032 -0.043734
+ 0.0012429
+ 0.0011504
+ 0.0013651
+ 0.0004494
+ 0.00040922
+ 0.0002411
+
+
+
+
+ clavphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0256563401807859
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.207345117461045
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0932005826567324
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ acromioclavicular_r2
+
+ 0.15709493 0.94726859 -0.27929088
+
+
+
+ 1 0
+
+
+
+
+
+ acromioclavicular_r3
+
+ -0.75408404 0.29759402 0.58548703
+
+
+
+ 1 0
+
+
+
+
+
+ acromioclavicular_r1
+
+ 0.63769985 0.11859997 0.76109982
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ scapula.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ 3.13042 -1.54881 -1.31423
+ -0.0058 -0.0378 0.0096
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 3.13042 -1.54881 -1.31423 -0.0058 -0.0378 0.0096
+
+ false
+
+ 0
+
+ 0.033 0.04 0.035
+
+
+
+ 0
+ 0.620988 0.32882 -0.560774
+ -0.0973 -0.0428 -0.037
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.620988 0.32882 -0.560774 -0.0973 -0.0428 -0.037
+
+ false
+
+ 0
+
+ 0.04
+ 0.06
+
+
+
+ 0
+ 0.0253073 0.58835 0.151844
+ -0.0561 -0.0199 -0.0112
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0253073 0.58835 0.151844 -0.0561 -0.0199 -0.0112
+
+ false
+
+ 0
+
+ 0.008
+ 0.019
+
+
+
+ 0
+ -2.09754 -0.280823 -1.76348
+ -0.0418 -0.0519 -0.0359
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -2.09754 -0.280823 -1.76348 -0.0418 -0.0519 -0.0359
+
+ false
+
+ 0
+
+ 0.03 0.03 0.05
+
+
+
+ 0
+ 1.37532 -0.294612 2.43596
+ -0.0359 -0.0309 -0.0132
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.37532 -0.294612 2.43596 -0.0359 -0.0309 -0.0132
+
+ false
+
+ 0
+
+ 0.003
+ 0.03
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ scapula
+
+ -0.00955 -0.034 0.009
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -0.0932005826567324
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ -0.207345117461045
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0.0256563401807859
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ unrothum_r1
+
+ 0.63769985 0.11859997 0.76109982
+
+
+
+ 1 0
+
+
+
+
+
+ unrothum_r3
+
+ -0.75408404 0.29759402 0.58548703
+
+
+
+ 1 0
+
+
+
+
+
+ unrothum_r2
+
+ 0.15709493 0.94726859 -0.27929088
+
+
+
+ 1 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ scapphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.57079633 2.26892803
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ elv_angle
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.04240001 0 -0.0048
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1
+ 1
+ 1
+ 0
+ 0
+ 0
+
+
+
+
+ humphant
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0.523598779689508
+
+ 0
+
+ 0 3.14159265
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ shoulder_elv
+
+ -0.99826136 0.0023 0.05889802
+
+
+
+ 1 0
+
+
+
+
+
+ shoulder1_r2
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ -0.05874685 0.042609 -0.99736316
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+
+
+ 1.99757
+ 0.018064 -0.140141 -0.012746
+ 0.01227763
+ 0.00255133
+ 0.01257888
+ -0.00034741
+ -0.0002325
+ 0.0012293
+
+
+
+
+ humphant1
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.57079633 0.34906585
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ shoulder_rot
+
+ 0.0048 0.99908918 0.04240001
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.04240001 0 -0.0048
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ humerus.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.0584685 1.00461 0.570374
+ -0.0139 -0.0127 -0.0262
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0584685 1.00461 0.570374 -0.0139 -0.0127 -0.0262
+
+ false
+
+ 0
+
+ 0.03 0.1 0.05
+
+
+
+ 0
+ 1.55093 -0.0199582 0.0596618
+ 0.0017 -0.0958 0.0011
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.55093 -0.0199582 0.0596618 0.0017 -0.0958 0.0011
+
+ false
+
+ 0
+
+ 0.0109
+ 0.12
+
+
+
+ 0
+ 1.72735 0.0759218 -2.74313
+ 0.0019 -0.0592 0.0011
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.72735 0.0759218 -2.74313 0.0019 -0.0592 0.0011
+
+ false
+
+ 0
+
+ 0.01 0.01 0.05
+
+
+
+ 0
+ 0.0380482 0.00855211 -1.30673
+ 0.0002 0.0077 0.0043
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.0380482 0.00855211 -1.30673 0.0002 0.0077 0.0043
+
+ false
+
+ 0
+
+ 0.02 0.02 0.02
+
+
+
+ 0
+ -0.286583 -0.00907571 -0.0684169
+ -0.0003 0.0026 0.0038
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.286583 -0.00907571 -0.0684169 -0.0003 0.0026 0.0038
+
+ false
+
+ 0
+
+ 0.02 0.025 0.02
+
+
+
+ 0
+ -0.924501 0.288852 0.381529
+ -0.0025 0.0007 -0.0045
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.924501 0.288852 0.381529 -0.0025 0.0007 -0.0045
+
+ false
+
+ 0
+
+ 0.02 0.017 0.028
+
+
+
+ 0
+ 1.75353 0.0692896 2.74628
+ -0.0014 -0.0455 0
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.75353 0.0692896 2.74628 -0.0014 -0.0455 0
+
+ false
+
+ 0
+
+ 0.007
+ 0.07
+
+
+
+ 0
+ 1.53641 -0.0637045 1.41424
+ 0.0007 -0.0443 -0.0055
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.53641 -0.0637045 1.41424 0.0007 -0.0443 -0.0055
+
+ false
+
+ 0
+
+ 0.007
+ 0.04
+
+
+
+ 0
+ 1.55928 -0.0774926 -0.925897
+ 0.002 -0.0508 -0.0017
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.55928 -0.0774926 -0.925897 0.002 -0.0508 -0.0017
+
+ false
+
+ 0
+
+ 0.009
+ 0.07
+
+
+
+ 0
+ 0 0 0
+ -0.0086 0.0021 -0.0004
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 -0.0086 0.0021 -0.0004
+
+ false
+
+ 0
+
+ 0.02
+
+
+
+ 0
+ -0.620465 -0.310494 0.363727
+ -0.0037 0.0005 -0.0025
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.620465 -0.310494 0.363727 -0.0037 0.0005 -0.0025
+
+ false
+
+ 0
+
+ 0.03 0.02 0.02
+
+
+
+ 0
+ 1.44094 -0.0561996 1.75196
+ 0.0009 -0.0551 -0.0004
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.44094 -0.0561996 1.75196 0.0009 -0.0551 -0.0004
+
+ false
+
+ 0
+
+ 0.008
+ 0.1
+
+
+
+ 0
+ -0.305084 -0.018326 -0.686613
+ -0.0224 0.0102 0.0094
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.305084 -0.018326 -0.686613 -0.0224 0.0102 0.0094
+
+ false
+
+ 0
+
+ 0.007
+ 0.045
+
+
+
+ 0
+ -0.127235 0.276111 0.0197222
+ -0.0016 0.0092 0.0052
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.127235 0.276111 0.0197222 -0.0016 0.0092 0.0052
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ -0.128631 0.137532 0.0307178
+ 0.0019 -0.289 -0.014
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.128631 0.137532 0.0307178 0.0019 -0.289 -0.014
+
+ false
+
+ 0
+
+ 0.015 0.015 0.1
+
+
+
+ 0
+ 3.00162 -0.853466 2.57419
+ -0.0078 -0.0041 -0.0014
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 3.00162 -0.853466 2.57419 -0.0078 -0.0041 -0.0014
+
+ false
+
+ 0
+
+ 0.035 0.02 0.02
+
+
+
+ 0
+ -0.14015 -0.00628319 0.154985
+ 0.0028 -0.2919 -0.0119
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.14015 -0.00628319 0.154985 0.0028 -0.2919 -0.0119
+
+ false
+
+ 0
+
+ 0.016
+ 0.1
+
+
+
+ 0
+ 0.00750492 -0.196699 1.04929
+ 0.0134 -0.2861 -0.0008
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.00750492 -0.196699 1.04929 0.0134 -0.2861 -0.0008
+
+ false
+
+ 0
+
+ 0.02 0.02 0.02
+
+
+
+ 0
+ -2.00434 -1.00164 0.975465
+ 0.0033 0.0073 0.0003
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -2.00434 -1.00164 0.975465 0.0033 0.0073 0.0003
+
+ false
+
+ 0
+
+ 0.025 0.02 0.02
+
+
+
+ 0
+ 0 0 0
+ 0.0007 0 0.006
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0.0007 0 0.006
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ 0 0 0
+ 0.0007 0 0.006
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0.0007 0 0.006
+
+ false
+
+ 0
+
+ 0.03
+
+
+
+ 0
+ -1.60832 0.0959931 0.875283
+ 0.0027 -0.1202 -0.0059
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.60832 0.0959931 0.875283 0.0027 -0.1202 -0.0059
+
+ false
+
+ 0
+
+ 0.008
+ 0.1
+
+
+
+ 0
+ -0.161094 -0.110828 0.61453
+ 0.003 -0.2872 -0.0069
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.161094 -0.110828 0.61453 0.003 -0.2872 -0.0069
+
+ false
+
+ 0
+
+ 0.018 0.025 0.035
+
+
+
+
+
+
+ 1.1053
+ 0.00971783 -0.0959509 0.024286
+ 0.00541309
+ 0.00115318
+ 0.00494361
+ 0.00031686
+ -7.615e-005
+ 0.00109169
+
+
+
+
+ humerus
+
+ 0.0061 -0.2904 -0.0123
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -1.99870688474894e-008
+
+ 0
+
+ 0 2.26892803
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ elbow_flexion
+
+ 0.04940001 0.03660001 0.99810825
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0.99810825 0 -0.04940001
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ ulna.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ 1.39138 0.0689405 1.52245
+ -0.0012 -0.2092 0.0428
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.39138 0.0689405 1.52245 -0.0012 -0.2092 0.0428
+
+ false
+
+ 0
+
+ 0.007
+ 0.1
+
+
+
+
+
+
+ 0.23359
+ 0.0336341 -0.181559 0.0156
+ 0.00043855
+ 8.859e-005
+ 0.00040258
+ 3.014e-005
+ -4.24e-006
+ 6.418e-005
+
+
+
+
+ ulna
+
+ 0.0004 -0.011503 0.019999
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ -2e-008
+
+ 0
+
+ -1.57079633 1.57079633
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ pro_sup
+
+ -0.01716099 0.99266564 -0.11966796
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ -0.11966796 0 0.01716099
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ radius.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 1.44775 0.304036 -2.44102
+ 0.0045 -0.0437 0.0059
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.44775 0.304036 -2.44102 0.0045 -0.0437 0.0059
+
+ false
+
+ 0
+
+ 0.008
+ 0.04
+
+
+
+ 0
+ -0.986635 -0.148877 0.222704
+ -0.0163 -0.2417 0.0349
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.986635 -0.148877 0.222704 -0.0163 -0.2417 0.0349
+
+ false
+
+ 0
+
+ 0.006
+ 0.009
+
+
+
+ 0
+ -1.60762 -0.0127409 -2.69025
+ 0.0281 -0.1986 0.0288
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.60762 -0.0127409 -2.69025 0.0281 -0.1986 0.0288
+
+ false
+
+ 0
+
+ 0.01
+ 0.1
+
+
+
+
+
+
+ 0.0001
+ 0 0 0
+ 1e-005
+ 1e-005
+ 1e-005
+ 0
+ 0
+ 0
+
+
+
+
+ radius
+
+ 0.018 -0.242 0.025
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -0.17453293 0.43633231
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -1.22173048 1.22173048
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ deviation
+
+ -0.819064 -0.135611 -0.557444
+
+
+
+ -0.174533 0 0.436332
+ -0.174533 0 0.436332
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+ flexion
+
+ 0.95642673 -0.25220693 0.14710396
+
+
+
+ -1.5708 1.5708
+ -0.785398 0.785398
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ lunate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastSCAPHOIDw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastPISIFORMw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfastTRIQUETRALw.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 0
+
+
+
+
+
+ 0
+ -0.250804 0.285536 0.232827
+ 0.0007 -0.0135 0.0047
+ true
+ z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.250804 0.285536 0.232827 0.0007 -0.0135 0.0047
+
+ false
+
+ 0
+
+ 0.05 0.02 0.013
+
+
+
+ 0
+ 1.53833 0.234398 0.731118
+ 0.0222 -0.0096 0.0208
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.53833 0.234398 0.731118 0.0222 -0.0096 0.0208
+
+ false
+
+ 0
+
+ 0.008
+ 0.016
+
+
+
+ 0
+ 1.31266 -0.11781 -0.116239
+ 0.0126 -0.0095 0.0186
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.31266 -0.11781 -0.116239 0.0126 -0.0095 0.0186
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -1.55596 -0.15324 -0.100007
+ 0.0032 -0.0045 -0.019
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.55596 -0.15324 -0.100007 0.0032 -0.0045 -0.019
+
+ false
+
+ 0
+
+ 0.001
+ 0.0025
+
+
+
+ 0
+ -1.57376 -0.0797616 0.39235
+ -0.0123 -0.0124 -0.0171
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57376 -0.0797616 0.39235 -0.0123 -0.0124 -0.0171
+
+ false
+
+ 0
+
+ 0.0068
+ 0.008
+
+
+
+ 0
+ -0.0315905 0.0996583 0.0633554
+ 0.0057 -0.018 -0.0041
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.0315905 0.0996583 0.0633554 0.0057 -0.018 -0.0041
+
+ false
+
+ 0
+
+ 0.025 0.014 0.012
+
+
+
+ 0
+ 0.00837758 -0.0816814 -0.0171042
+ 0.0012 -0.0057 -0.0003
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.00837758 -0.0816814 -0.0171042 0.0012 -0.0057 -0.0003
+
+ false
+
+ 0
+
+ 0.025 0.013 0.012
+
+
+
+ 0
+ -1.46747 -0.194604 0.121824
+ -0.0022 -0.0069 0.0032
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.46747 -0.194604 0.121824 -0.0022 -0.0069 0.0032
+
+ false
+
+ 0
+
+ 0.025 0.013 0.012
+
+
+
+ 0
+ 2.36318 0.193033 -0.26913
+ -0.0128 -0.0133 0.0148
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.36318 0.193033 -0.26913 -0.0128 -0.0133 0.0148
+
+ false
+
+ 0
+
+ 0.008
+ 0.012
+
+
+
+ 0
+ 1.98392 0.100531 0.523075
+ -0.0098 -0.0137 0.0166
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.98392 0.100531 0.523075 -0.0098 -0.0137 0.0166
+
+ false
+
+ 0
+
+ 0.0105
+ 0.011
+
+
+
+ 0
+ 1.99317 0.19792 0.368264
+ -0.0007 -0.0117 0.0191
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.99317 0.19792 0.368264 -0.0007 -0.0117 0.0191
+
+ false
+
+ 0
+
+ 0.009
+ 0.012
+
+
+
+ 0
+ 1.69768 0.0897099 0.00767945
+ 0.009 -0.0149 0.0211
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.69768 0.0897099 0.00767945 0.009 -0.0149 0.0211
+
+ false
+
+ 0
+
+ 0.009
+ 0.012
+
+
+
+ 0
+ 2.9627 0.159349 0.117984
+ -0.0167 -0.0022 0.0048
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.9627 0.159349 0.117984 -0.0167 -0.0022 0.0048
+
+ false
+
+ 0
+
+ 0.018 0.014 0.008
+
+
+
+ 0
+ -0.16633 -0.082205 -0.0659735
+ 0.017 -0.025 -0.0033
+ true
+ -z
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.16633 -0.082205 -0.0659735 0.017 -0.025 -0.0033
+
+ false
+
+ 0
+
+ 0.016 0.01 0.01
+
+
+
+
+
+
+ 0.5819
+ -0.00301314 -0.0424993 -0.00112205
+ 0.00011
+ 6e-005
+ 0.00015
+ 9e-007
+ -2e-007
+ 1.2e-005
+
+
+
+
+ proximal_row
+
+ 0.003992 -0.015054 0.002327
+
+ 0 0 0
+
+ 0 0 0
+
+ 0 0 0
+
+
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+ rotational
+
+ 0
+
+ 0
+
+ -99999.9 99999.9
+
+ false
+
+ false
+
+
+
+ false
+
+
+
+
+
+ false
+
+
+
+
+
+ wrist_hand_r1
+
+ 0.8991357 -0.34905288 -0.26403991
+
+
+
+ 1 0
+
+
+
+
+
+ wrist_hand_r3
+
+ 0.99711853 0.01069999 -0.07510096
+
+
+
+ 1 0
+
+
+
+
+
+
+
+ 0.02903943 -0.19575313 0.35766784
+
+
+
+ 0
+
+
+
+
+
+
+
+
+ 1 0 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 1 0
+
+
+
+ 0
+
+
+
+
+
+
+
+ 0 0 1
+
+
+
+ 0
+
+
+
+
+
+
+
+
+
+
+
+
+ sdfast_1seg_hand_fr_c_5mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_4mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_3mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_2mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_trapezium.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_trapezoid.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ sdfast_1seg_hand_fr_c_hamate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ capitate.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_2distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_3distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_4distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5proxph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5midph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_5distph.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_thumbprox.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_thumbdist.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+ hand_1mc.vtp
+
+ 1 1 1
+
+
+
+ 0 0 0 0 0 0
+
+ 1 1 1
+
+ 4
+
+ 1
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+
+
+ 0
+ 0.593936 1.50011 -2.16578
+ 0.0182 -0.0659 0.0087
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -2.16578 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.593936 1.50011 -2.23559
+ 0.0182 -0.0659 0.0087
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -2.23559 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.593936 1.50011 -1.99125
+ 0.0182 -0.0659 0.0087
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.593936 1.50011 -1.99125 0.0182 -0.0659 0.0087
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 1.48667 -1.29661 2.43072
+ 0.0206 -0.068 0.0044
+ false
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.48667 -1.29661 2.43072 0.0206 -0.068 0.0044
+
+ false
+
+ 0
+
+ 0.005 0.005 0.03
+
+
+
+ 0
+ 0.770388 1.32837 1.5708
+ 0.0007 -0.0655 0.0092
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.5708 0.0007 -0.0655 0.0092
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.770388 1.32837 1.5708
+ 0.0046 -0.0662 0.0099
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.5708 0.0046 -0.0662 0.0099
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.770388 1.32837 1.46608
+ 0.0007 -0.0655 0.0092
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.770388 1.32837 1.46608 0.0007 -0.0655 0.0092
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -2.48535
+ -0.0139 -0.0642 0.0033
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -2.48535 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.013
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -2.48535
+ -0.0139 -0.0642 0.0033
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -2.48535 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.858527 1.10165 -3.09621
+ -0.0139 -0.0642 0.0033
+ true
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.858527 1.10165 -3.09621 -0.0139 -0.0642 0.0033
+
+ false
+
+ 0
+
+ 0.01
+ 0.01
+
+
+
+ 0
+ 0.470541 0.975639 -2.12162
+ -0.0235 -0.0561 -0.0057
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -2.12162 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.013
+ 0.012
+
+
+
+ 0
+ 0.470541 0.975639 -2.34852
+ -0.0235 -0.0561 -0.0057
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -2.34852 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.0105
+ 0.01
+
+
+
+ 0
+ 0.470541 0.975639 -1.68529
+ -0.0235 -0.0561 -0.0057
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.470541 0.975639 -1.68529 -0.0235 -0.0561 -0.0057
+
+ false
+
+ 0
+
+ 0.01
+ 0.012
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -1.57813 1.24808 1.0259
+ 0.0307 -0.0924 -0.0222
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.57813 1.24808 1.0259 0.0307 -0.0924 -0.0222
+
+ false
+
+ 0
+
+ 0.0055
+ 0.012
+
+
+
+ 0
+ -1.63171 1.34286 2.11639
+ 0.0291 -0.0821 -0.045
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.63171 1.34286 2.11639 0.0291 -0.0821 -0.045
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ -1.63171 1.34286 2.11639
+ 0.0291 -0.0821 -0.045
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -1.63171 1.34286 2.11639 0.0291 -0.0821 -0.045
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 2.2513 -1.37008 1.18159
+ 0.0306 -0.0911 -0.0223
+ false
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 2.2513 -1.37008 1.18159 0.0306 -0.0911 -0.0223
+
+ false
+
+ 0
+
+ 0.004
+ 0.01
+
+
+
+ 0
+ 1.35525 -1.38387 -0.557109
+ 0.0295 -0.0815 -0.0441
+ false
+ x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 1.35525 -1.38387 -0.557109 0.0295 -0.0815 -0.0441
+
+ false
+
+ 0
+
+ 0.003
+ 0.01
+
+
+
+ 0
+ 0.321315 0.11013 -0.834791
+ 0.0402 -0.0405 -0.0271
+ true
+ all
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.321315 0.11013 -0.834791 0.0402 -0.0405 -0.0271
+
+ false
+
+ 0
+
+ 0.0085
+ 0.02
+
+
+
+ 0
+ 0.332136 -0.026529 -0.257611
+ 0.0396 -0.0713 -0.0365
+ true
+ -x
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.332136 -0.026529 -0.257611 0.0396 -0.0713 -0.0365
+
+ false
+
+ 0
+
+ 0.0045
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ -0.407883 1.45246 -0.145386
+ 0.0122 -0.0934 -0.0238
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ -0.407883 1.45246 -0.145386 0.0122 -0.0934 -0.0238
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.714189 1.28282 -0.203331
+ 0.019 -0.0814 -0.0494
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.714189 1.28282 -0.203331 0.019 -0.0814 -0.0494
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.714189 1.28282 -0.203331
+ 0.019 -0.0814 -0.0494
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.714189 1.28282 -0.203331 0.019 -0.0814 -0.0494
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ 0.696212 0.976861 -1.21876
+ -0.005 -0.0871 -0.0289
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.696212 0.976861 -1.21876 -0.005 -0.0871 -0.0289
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.75311 0.925897 -0.167377
+ 0.0094 -0.0778 -0.0469
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.75311 0.925897 -0.167377 0.0094 -0.0778 -0.0469
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.75311 0.925897 -0.167377
+ 0.0094 -0.0778 -0.0469
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.75311 0.925897 -0.167377 0.0094 -0.0778 -0.0469
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.51687
+ -0.0154 -0.0784 -0.0329
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.51687 -0.0154 -0.0784 -0.0329
+
+ false
+
+ 0
+
+ 0.0075
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.79612
+ -0.0153 -0.0786 -0.0329
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.79612 -0.0153 -0.0786 -0.0329
+
+ false
+
+ 0
+
+ 0.008
+ 0.01
+
+
+
+ 0
+ 0.977035 0.825192 -1.08053
+ -0.0152 -0.0785 -0.0328
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.977035 0.825192 -1.08053 -0.0152 -0.0785 -0.0328
+
+ false
+
+ 0
+
+ 0.0055
+ 0.01
+
+
+
+ 0
+ 0.979304 0.65031 -0.620814
+ 0.0007 -0.0741 -0.0457
+ true
+ y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.979304 0.65031 -0.620814 0.0007 -0.0741 -0.0457
+
+ false
+
+ 0
+
+ 0.005
+ 0.01
+
+
+
+ 0
+ 0.979304 0.65031 -0.620814
+ 0.007 -0.0741 -0.0457
+ true
+ -y
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0.979304 0.65031 -0.620814 0.007 -0.0741 -0.0457
+
+ false
+
+ 0
+
+ 0.002
+ 0.01
+
+
+
+
+
+
+
+
+
+
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.633555
+
+
+
+ shoulder_elv
+
+ sternoclavicular_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 3.14159
+ 0 0.322013
+
+
+
+ shoulder_elv
+
+ sternoclavicular_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.633555
+
+
+
+ shoulder_elv
+
+ unrotscap_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 3.14159
+ 0 -0.322013
+
+
+
+ shoulder_elv
+
+ unrotscap_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.466003
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r1
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.128282
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 1.03673
+
+
+
+ shoulder_elv
+
+ acromioclavicular_r3
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -0.466003
+
+
+
+ shoulder_elv
+
+ unrothum_r1
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 0.128282
+
+
+
+ shoulder_elv
+
+ unrothum_r2
+
+ 1
+
+
+
+ false
+
+
+
+ 0 2.61799
+ 0 -1.03673
+
+
+
+ shoulder_elv
+
+ unrothum_r3
+
+ 1
+
+
+
+ false
+
+
+
+ -1.5708 3.14159
+ 1.5708 -3.14159
+
+
+
+ elv_angle
+
+ shoulder1_r2
+
+ 1
+
+
+
+ false
+
+
+
+ -0.174533 0 0.436332
+ -0.261799 0 0.436332
+
+
+
+ deviation
+
+ wrist_hand_r1
+
+ 1
+
+
+
+ false
+
+
+
+ -1.22173 1.22173
+ -0.610865 0.610865
+
+
+
+ flexion
+
+ wrist_hand_r3
+
+ 1
+
+
+
+
+
+
+
+
+
+ false
+
+ shoulder_elv
+
+ 100
+
+ 150
+
+ 100
+
+ 30
+
+ 0
+
+ 542.8423
+
+
+
+ false
+
+ shoulder_elv
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ elv_angle
+
+ 100
+
+ 100
+
+ 100
+
+ -60
+
+ 0
+
+ 545.4471
+
+
+
+ false
+
+ elv_angle
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ shoulder_rot
+
+ 100
+
+ -10
+
+ 100
+
+ -60
+
+ 0
+
+ 485.466
+
+
+
+ false
+
+ shoulder_rot
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ elbow_flexion
+
+ 0.3037
+
+ 85
+
+ 100
+
+ 14
+
+ 0
+
+ 139.5813
+
+
+
+ false
+
+ elbow_flexion
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ pro_sup
+
+ 50
+
+ 60
+
+ 50
+
+ -60
+
+ 0
+
+ 430.1186
+
+
+
+ false
+
+ pro_sup
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ deviation
+
+ 52.5961
+
+ 20
+
+ 487.176
+
+ -6
+
+ 0
+
+ 39.1586
+
+
+
+ false
+
+ deviation
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.001745
+
+ 1
+
+
+
+ false
+
+ flexion
+
+ 200
+
+ 60
+
+ 135.3232
+
+ -60
+
+ 0
+
+ 92.916
+
+
+
+ false
+
+ flexion
+
+ 1e-008
+
+ 190
+
+ 1e-008
+
+ 190
+
+ 0.00043633
+
+ 1
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00896 -0.11883 0.00585
+ humerus
+
+
+ 0.01623 -0.11033 0.00412
+ humerus
+
+
+ 0.04347 -0.03252 0.00099
+ scapula
+
+
+ -0.014 0.01106 0.08021
+ clavicle
+
+
+
+
+
+
+
+
+ delt2hum
+ hybrid
+ -1 -1
+
+
+ DELT1hh
+ hybrid
+ 2 3
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1218.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.05573 0.00122 -0.02512
+ scapula
+
+
+ -0.07247 -0.03285 0.01233
+ scapula
+
+
+ 0.00206 -0.07602 0.01045
+ humerus
+
+
+
+
+
+
+
+
+ Delt3
+ hybrid
+ 1 2
+
+
+ delt3hum
+ hybrid
+ -1 -1
+
+
+ DELT_TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 201.6
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00256 0.01063 0.02593
+ humerus
+
+
+ -0.01918 0.00127 -0.01271
+ scapula
+
+
+ -0.044 -0.01512 -0.05855
+ scapula
+
+
+
+
+
+
+
+
+ SUPSP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 499.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00887 0.00484 0.02448
+ humerus
+
+
+ -0.07382 -0.05476 -0.04781
+ scapula
+
+
+
+
+
+
+
+
+ INFSP
+ hybrid
+ -1 -1
+
+
+ INFSP_and_TMIN_hum_head
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1075.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01403 0.0084 -0.01331
+ humerus
+
+
+ -0.01831 -0.05223 -0.02457
+ scapula
+
+
+ -0.07246 -0.03943 -0.06475
+ scapula
+
+
+
+
+
+
+
+
+ SUBSCAP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1306.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0011 -0.01264 0.02156
+ humerus
+
+
+ -0.09473 -0.07991 -0.04737
+ scapula
+
+
+ -0.09643 -0.08121 -0.05298
+ scapula
+
+
+
+
+
+
+
+
+ TMIN
+ hybrid
+ 1 2
+
+
+ INFSP_and_TMIN_hum_head
+ hybrid
+ 1 2
+
+
+ TMINhum
+ hybrid
+ 1 2
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 269.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00998 -0.05419 -0.00568
+ humerus
+
+
+ -0.10264 -0.10319 -0.05829
+ scapula
+
+
+ -0.10489 -0.10895 -0.07117
+ scapula
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 144
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01169 -0.04191 0.0078
+ humerus
+
+
+ 0.0171333 -0.037 -0.00337
+ humerus
+
+
+ 0 3.14159
+ 0.01615 0.02205
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04045 -0.01975
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.00577 0.00863
+
+
+ shoulder_elv
+
+
+ 0.00636333 -0.00732333 0.119273
+ ground
+
+
+ 0 3.14159
+ 0.00958 -0.00972
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.01509 0.03151
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.12664 0.08244
+
+
+ shoulder_elv
+
+
+ 0.00321 -0.00013 0.05113
+ clavicle
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC12hum
+ hybrid
+ 2 3
+
+
+ PEC1hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 444.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01274 -0.04289 0.00785
+ humerus
+
+
+ 0.0155133 -0.04223 -0.00447
+ humerus
+
+
+ 0 3.14159
+ 0.01453 0.02043
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04568 -0.02498
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.00687 0.00753
+
+
+ shoulder_elv
+
+
+ 0.0203967 -0.03445 0.123117
+ ground
+
+
+ 0 3.14159
+ 0.02018 0.02148
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04165 0.00155
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.1269 0.1042
+
+
+ shoulder_elv
+
+
+ 0.03091 -0.03922 0.09705
+ ground
+
+
+ 0.02769 -0.04498 0.02271
+ ground
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC12hum
+ hybrid
+ 2 3
+
+
+ TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+ PEC23hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 658.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01269 -0.04375 0.0075
+ humerus
+
+
+ 0.0142392 -0.0496515 -0.00936368
+ humerus
+
+
+ 0 0.747517 3.14159
+ 0.01243 0.014912 0.01833
+
+
+ shoulder_elv
+
+
+ 0 3.13149
+ -0.05157 -0.040096
+
+
+ shoulder_elv
+
+
+ 0 0.623056 2.29124 3.12533
+ -0.01807 -0.008102 0.000123 -0.000324
+
+
+ shoulder_elv
+
+
+ 0.02984 -0.0697393 0.1151
+ ground
+
+
+ 0 3.14159
+ 0.02984 0.02984
+
+
+ shoulder_elv
+
+
+ 0.0101016 1.59605 3.14159
+ -0.070778 -0.059781 -0.0269
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ 0.1151 0.1151
+
+
+ shoulder_elv
+
+
+ 0.0525 -0.08417 0.08935
+ ground
+
+
+ 0.05724 -0.11654 0.03787
+ ground
+
+
+
+
+
+
+
+
+ Thorax
+ hybrid
+ -1 -1
+
+
+ PEC3hum
+ hybrid
+ 2 3
+
+
+ PEC23hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 498.1
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0105 -0.03415 -0.00653
+ humerus
+
+
+ -0.07982 -0.0799433 -0.02428
+ scapula
+
+
+ 0 3.14159
+ -0.07947 -0.08157
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.08581 -0.05061
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.02188 -0.03628
+
+
+ shoulder_elv
+
+
+ -0.111183 -0.0893233 -0.06022
+ scapula
+
+
+ 0 3.14159
+ -0.11215 -0.10635
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.09779 -0.04699
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.05322 -0.09522
+
+
+ shoulder_elv
+
+
+ -0.11828 -0.10118 0.03316
+ ground
+
+
+ -0.09578 -0.11724 0.00882
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 290.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00968 -0.04071 -0.00611
+ humerus
+
+
+ -0.07875 -0.0971167 -0.02023
+ scapula
+
+
+ 0 3.14159
+ -0.0764 -0.0905
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.1022 -0.0717
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.01808 -0.03098
+
+
+ shoulder_elv
+
+
+ -0.10544 -0.128957 -0.0645967
+ scapula
+
+
+ 0 3.14159
+ -0.10054 -0.12994
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.13969 -0.07529
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.05258 -0.12468
+
+
+ shoulder_elv
+
+
+ -0.10992 -0.16908 0.02878
+ ground
+
+
+ -0.07186 -0.18818 0.00815
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 317.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01208 -0.03922 -0.00416
+ humerus
+
+
+ -0.06598 -0.127347 -0.0241833
+ scapula
+
+
+ 0 3.14159
+ -0.05678 -0.11198
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.13303 -0.09893
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.0213 -0.0386
+
+
+ shoulder_elv
+
+
+ -0.10059 -0.16313 -0.0590767
+ scapula
+
+
+ 0 3.14159
+ -0.09449 -0.13109
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.17553 -0.10113
+
+
+ shoulder_elv
+
+
+ 0 3.14159
+ -0.04406 -0.13416
+
+
+ shoulder_elv
+
+
+ -0.11157 -0.19387 0.05532
+ ground
+
+
+ -0.07117 -0.24858 0.00907
+ ground
+
+
+
+
+
+
+
+
+ TMAJ_LAThum
+ hybrid
+ -1 -1
+
+
+ LAT_TMAJhh
+ hybrid
+ 1 2
+
+
+ LAT_TMAJ2hh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 189
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0125 -0.04127 -0.02652
+ scapula
+
+
+ 0.00483 -0.06958 -0.01563
+ scapula
+
+
+ 0.00743 -0.15048 -0.00782
+ humerus
+
+
+
+
+
+
+
+
+ CORBhum
+ hybrid
+ -1 -1
+
+
+ TMAJ_LAT_PEC_CORBhh
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 208.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.04565 -0.04073 -0.01377
+ scapula
+
+
+ -0.02714 -0.11441 -0.00664
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+ TRIlonghh
+ hybrid
+ -1 -1
+
+
+ TRIlongglen
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 771.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00599 -0.12646 0.00428
+ humerus
+
+
+ -0.02344 -0.14528 0.00928
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 717.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00838 -0.13695 -0.00906
+ humerus
+
+
+ -0.02601 -0.15139 -0.0108
+ humerus
+
+
+ -0.03184 -0.22637 -0.01217
+ humerus
+
+
+ -0.01743 -0.26757 -0.01208
+ humerus
+
+
+ -0.0219 0.01046 -0.00078
+ ulna
+
+
+
+
+
+
+
+
+ TRI
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 717.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00744 -0.28359 0.00979
+ humerus
+
+
+ -0.02532 -0.00124 0.006
+ ulna
+
+
+
+
+
+
+
+
+ ANC
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 283.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00996 -0.06096 0.00075
+ radius
+
+
+ 0.01201 -0.0517 -0.00107
+ radius
+
+
+ -0.0136 -0.03384 0.02013
+ ulna
+
+
+
+
+
+
+
+
+ SUP
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 379.6
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0068 -0.1739 -0.0036
+ humerus
+
+
+ 0.01894 -0.28559 -0.01105
+ humerus
+ 0 0.813149
+ elbow_flexion
+
+
+ 0.00498 -0.01463 0.00128
+ ulna
+ 0 0.813149
+ elbow_flexion
+
+
+ -0.0032 -0.0239 0.0009
+ ulna
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 1177.37
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0098 -0.19963 0.00223
+ humerus
+
+
+ 0.03577 -0.12742 0.02315
+ radius
+
+
+ 0.0419 -0.221 0.0224
+ radius
+
+
+
+
+
+
+
+
+ Elbow_BIC_BRD
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 276
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0073 -0.2609 0.0091
+ humerus
+
+
+ 0.03195 -0.13463 0.02779
+ radius
+
+
+ 0.04243 -0.23684 0.0362
+ radius
+
+
+ 0.01717 -0.02122 0.00583
+ hand
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 337.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01349 -0.29048 0.01698
+ humerus
+
+
+ 0.02905 -0.13086 0.02385
+ radius
+
+
+ 0.03549 -0.22805 0.03937
+ radius
+
+
+ 0.005 -0.01136 0.0085
+ hand
+
+
+
+
+
+
+
+
+ ECRB
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 252.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00083 -0.28955 0.0188
+ humerus
+
+
+ -0.01391 -0.03201 0.02947
+ ulna
+
+
+ -0.01705 -0.05428 0.02868
+ ulna
+
+
+ -0.01793 -0.09573 0.03278
+ ulna
+
+
+ -0.01421 -0.22696 0.03481
+ radius
+
+
+ -0.02251 -0.01401 -0.00128
+ hand
+
+
+
+
+
+
+
+
+ ECU
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 192.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00758 -0.27806 -0.03705
+ humerus
+
+
+ 0.0211 -0.21943 0.00127
+ radius
+
+
+ 0.01124 -0.01844 -0.00418
+ hand
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ FCR
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 407.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00219 -0.2774 -0.0388
+ humerus
+
+
+ 0.00949 -0.1841 0.0005
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.00279 0.00949 0.01869
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.1838 -0.1841 -0.1821
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.0069 0.0005 0.0002
+
+
+ pro_sup
+
+
+ 0.01082 -0.22327 0.00969
+ radius
+
+
+ -0.02036 -0.01765 -0.00752
+ hand
+
+
+
+
+
+
+
+
+ FCU
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 479.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00457 -0.27519 -0.03865
+ humerus
+
+
+ 0.02531 -0.23915 -0.00276
+ radius
+
+
+ 0.00917 -0.01898 -0.01754
+ hand
+
+
+ 0.00227 -0.03096 0.00493
+ hand
+
+
+
+
+
+
+
+
+ PL
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 101
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.0036 -0.2759 -0.0365
+ humerus
+
+
+ 0.00846 -0.03373 -0.01432
+ ulna
+
+
+ 0.01219 -0.06516 -0.00219
+ ulna
+
+
+ -1.5708 1.5708
+ 0.01884 0.00554
+
+
+ pro_sup
+
+
+ -1.5708 1.5708
+ -0.06086 -0.06946
+
+
+ pro_sup
+
+
+ -1.5708 1.5708
+ 0.00506 -0.00944
+
+
+ pro_sup
+
+
+ 0.0236 -0.0934 0.0094
+ radius
+ -1.5708 0.509636
+ pro_sup
+
+
+ 0.0254 -0.1088 0.0198
+ radius
+
+
+
+
+
+
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 557.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.03245 -0.19998 0.01962
+ radius
+
+
+ 0.00193 -0.20972 0.03632
+ ulna
+
+
+
+
+
+
+
+
+ PQ2
+ hybrid
+ -1 -1
+
+
+ PQ1
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 284.7
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00421 -0.27598 -0.03864
+ humerus
+
+
+ 0.01377 -0.18718 0.00205
+ radius
+
+
+ -0.00235 -0.01393 -0.01376
+ hand
+
+
+ -0.01995 -0.04281 -0.00742
+ hand
+
+
+ -0.02044 -0.05981 -0.01878
+ hand
+
+
+ -0.01713 -0.07245 -0.02753
+ hand
+
+
+ -0.01156 -0.07271 -0.03656
+ hand
+
+
+ -0.01059 -0.07271 -0.03796
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ _5rdmcp_FDS
+ hybrid
+ 4 5
+
+
+ Fifthpm_FDS
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 75.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00479 -0.2788 -0.03731
+ humerus
+
+
+ 0.01571 -0.18666 0.00267
+ radius
+
+
+ -0.00082 -0.01344 -0.01359
+ hand
+
+
+ -0.00977 -0.05179 4e-005
+ hand
+
+
+ -0.01323 -0.0667 -0.0102
+ hand
+
+
+ -0.00788 -0.08027 -0.02503
+ hand
+
+
+ -0.00299 -0.08125 -0.03395
+ hand
+
+
+ 0.00062 -0.08092 -0.03892
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ Elbow_PT_ECRL
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_FDS
+ hybrid
+ 4 5
+
+
+ Fourthpm_FDS
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 171.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00669 -0.02713 -0.00191
+ ulna
+
+
+ 0.01899 -0.18706 0.00424
+ radius
+
+
+ 0.0068 -0.01377 -0.01399
+ hand
+
+
+ 0.00471 -0.03332 -0.00132
+ hand
+
+
+ 0.00542 -0.0566 0.0006
+ hand
+
+
+ 0.00555 -0.07224 -0.00338
+ hand
+
+
+ 0.01167 -0.0881 -0.0167
+ hand
+
+
+ 0.01301 -0.0887 -0.02977
+ hand
+
+
+ 0.01568 -0.08577 -0.03765
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ _3rdmcp_FDS
+ hybrid
+ 5 6
+
+
+ Thirdpm_FDS
+ hybrid
+ 7 8
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 258.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00676 -0.02819 -0.00137
+ ulna
+
+
+ 0.02145 -0.18623 0.00552
+ radius
+
+
+ 0.00889 -0.01366 -0.01387
+ hand
+
+
+ 0.01061 -0.03787 0.00024
+ hand
+
+
+ 0.01782 -0.05108 0.00418
+ hand
+
+
+ 0.01849 -0.07297 -0.00375
+ hand
+
+
+ 0.02678 -0.08714 -0.01804
+ hand
+
+
+ 0.02667 -0.0874 -0.02678
+ hand
+
+
+ 0.0266 -0.08633 -0.02903
+ hand
+
+
+
+
+
+
+
+
+ FDS
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_FDS
+ hybrid
+ 5 6
+
+
+ Secondpm_FDS
+ hybrid
+ 7 8
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 162.5
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00628 -0.03214 0.00254
+ ulna
+
+
+ 0.01409 -0.18516 0.00861
+ radius
+
+
+ -0.00088 -0.01027 -0.01188
+ hand
+
+
+ -0.01855 -0.04646 -0.00733
+ hand
+
+
+ -0.01808 -0.05841 -0.0156
+ hand
+
+
+ -0.01428 -0.07289 -0.02683
+ hand
+
+
+ -0.0092 -0.07483 -0.03684
+ hand
+
+
+ -0.00312 -0.07405 -0.04165
+ hand
+
+
+ 0.00446 -0.07059 -0.04657
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _5rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Fifthpm_FDP
+ hybrid
+ 6 7
+
+
+ Fifthmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 236.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00502 -0.03374 0.00273
+ ulna
+
+
+ 0.0158 -0.18629 0.00803
+ radius
+
+
+ 0.00106 -0.01177 -0.01184
+ hand
+
+
+ -0.00855 -0.05542 0.00088
+ hand
+
+
+ -0.01079 -0.06588 -0.00817
+ hand
+
+
+ -0.00547 -0.08154 -0.02256
+ hand
+
+
+ -0.00056 -0.0823 -0.03367
+ hand
+
+
+ 0.00609 -0.07837 -0.04238
+ hand
+
+
+ 0.01211 -0.0738 -0.04858
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Fourthpm_FDP
+ hybrid
+ 6 7
+
+
+ Fourthmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 172.9
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00522 -0.03327 0.0021
+ ulna
+
+
+ 0.01906 -0.18644 0.00785
+ radius
+
+
+ 0.00335 -0.0128 -0.01144
+ hand
+
+
+ 0.00302 -0.03447 -0.00611
+ hand
+
+
+ 0.00252 -0.05863 0.00122
+ hand
+
+
+ 0.00285 -0.06985 -0.00133
+ hand
+
+
+ 0.00863 -0.08779 -0.01815
+ hand
+
+
+ 0.01002 -0.08766 -0.02964
+ hand
+
+
+ 0.01633 -0.08157 -0.04435
+ hand
+
+
+ 0.01909 -0.07663 -0.05229
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _3rdmcp_FDP
+ hybrid
+ 5 6
+
+
+ Thirdpm_FDP
+ hybrid
+ 7 8
+
+
+ Thirdmd_flex
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 212.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00647 -0.03176 0.0028
+ ulna
+
+
+ 0.0208 -0.1856 0.00915
+ radius
+
+
+ 0.00896 -0.01168 -0.01212
+ hand
+
+
+ 0.01922 -0.05542 0.00438
+ hand
+
+
+ 0.02073 -0.07021 -0.00286
+ hand
+
+
+ 0.02904 -0.08588 -0.01782
+ hand
+
+
+ 0.02924 -0.08672 -0.02769
+ hand
+
+
+ 0.02914 -0.08235 -0.03979
+ hand
+
+
+ 0.02847 -0.07771 -0.04766
+ hand
+
+
+
+
+
+
+
+
+ FDP
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_FDP
+ hybrid
+ 4 5
+
+
+ Secondpm_FDP
+ hybrid
+ 6 7
+
+
+ Secondmd_flex
+ hybrid
+ 8 9
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 197.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.0004 -0.28831 0.0187
+ humerus
+
+
+ 0.0013 -0.03888 0.01405
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.0121 0.0013 -0.0095
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04018 -0.03888 -0.03508
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01055 0.01405 0.01316
+
+
+ pro_sup
+
+
+ 0.00993 -0.22304 0.03618
+ radius
+
+
+ -0.02464 -0.04402 0.00169
+ hand
+
+
+ -0.02381 -0.04734 0.00077
+ hand
+
+
+ -0.02395 -0.06613 -0.01001
+ hand
+
+
+ -0.01798 -0.07847 -0.02711
+ hand
+
+
+ -0.01178 -0.07877 -0.03779
+ hand
+
+
+ -0.0015 -0.07586 -0.04586
+ hand
+
+
+ 0.00201 -0.07487 -0.04794
+ hand
+
+
+
+
+
+
+
+
+ EDCL
+ hybrid
+ 3 4
+
+
+ _5rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Fifthpm_ext
+ hybrid
+ 7 8
+
+
+ Fifthmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 39.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00156 -0.28936 0.01782
+ humerus
+
+
+ 0.0026 -0.03991 0.01552
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.0134 0.0026 -0.0082
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04121 -0.03991 -0.03611
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01202 0.01552 0.01463
+
+
+ pro_sup
+
+
+ 0.00882 -0.22366 0.04284
+ radius
+
+
+ -0.01564 -0.0555 0.00934
+ hand
+
+
+ -0.01427 -0.05819 0.01161
+ hand
+
+
+ -0.0158 -0.07216 -0.00421
+ hand
+
+
+ -0.00825 -0.08735 -0.0226
+ hand
+
+
+ -0.00272 -0.08806 -0.03409
+ hand
+
+
+ 0.00763 -0.08026 -0.04658
+ hand
+
+
+ 0.01069 -0.07809 -0.04941
+ hand
+
+
+
+
+
+
+
+
+ EDCR
+ hybrid
+ -1 -1
+
+
+ _4rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Fourthpm_ext
+ hybrid
+ 7 8
+
+
+ Fourthmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 109.2
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00051 -0.28984 0.01949
+ humerus
+
+
+ 0.00316 -0.03948 0.01528
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.01396 0.00316 -0.00764
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04078 -0.03948 -0.03568
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01178 0.01528 0.01439
+
+
+ pro_sup
+
+
+ 0.0144 -0.22323 0.04223
+ radius
+
+
+ 0.00039 -0.05274 0.01491
+ hand
+
+
+ -0.00087 -0.05574 0.01452
+ hand
+
+
+ 0.00186 -0.07718 0.00597
+ hand
+
+
+ 0.01007 -0.09313 -0.01774
+ hand
+
+
+ 0.01321 -0.09558 -0.03056
+ hand
+
+
+ 0.01857 -0.08525 -0.04759
+ hand
+
+
+ 0.02056 -0.07993 -0.05341
+ hand
+
+
+ 0.02195 -0.07701 -0.05663
+ hand
+
+
+
+
+
+
+
+
+ EDCM
+ hybrid
+ 1 4
+
+
+ Thirdmd_ext
+ hybrid
+ 9 10
+
+
+ Thirdpm_ext
+ hybrid
+ 7 8
+
+
+ _3rdmcp_ext
+ hybrid
+ 5 6
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 94.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00065 -0.28898 0.01869
+ humerus
+
+
+ 0.00228 -0.03918 0.01483
+ radius
+
+
+ -1.5708 0 1.5708
+ 0.01308 0.00228 -0.00852
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ -0.04048 -0.03918 -0.03538
+
+
+ pro_sup
+
+
+ -1.5708 0 1.5708
+ 0.01133 0.01483 0.01394
+
+
+ pro_sup
+
+
+ 0.01533 -0.22314 0.04196
+ radius
+
+
+ 0.01543 -0.0468 0.01639
+ hand
+
+
+ 0.01897 -0.05654 0.01438
+ hand
+
+
+ 0.01994 -0.07678 0.00594
+ hand
+
+
+ 0.02945 -0.09162 -0.01245
+ hand
+
+
+ 0.03121 -0.09349 -0.02905
+ hand
+
+
+ 0.03013 -0.08487 -0.04268
+ hand
+
+
+ 0.02929 -0.08103 -0.04966
+ hand
+
+
+
+
+
+
+
+
+ EDCI
+ hybrid
+ 3 4
+
+
+ _2rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Secondpm_ext
+ hybrid
+ 7 8
+
+
+ Secondmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 48.8
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00089 -0.28919 0.01847
+ humerus
+
+
+ -0.00977 -0.03907 0.03085
+ ulna
+
+
+ -0.00755 -0.08267 0.03646
+ ulna
+
+
+ 0.00454 -0.22641 0.03678
+ radius
+
+
+ -0.02059 -0.01032 0.00372
+ hand
+
+
+ -0.02563 -0.04722 0.00023
+ hand
+
+
+ -0.02549 -0.06511 -0.01098
+ hand
+
+
+ -0.01933 -0.0781 -0.02718
+ hand
+
+
+ -0.01346 -0.07892 -0.03894
+ hand
+
+
+ -0.00216 -0.07521 -0.04589
+ hand
+
+
+ 0.00132 -0.07345 -0.04803
+ hand
+
+
+
+
+
+
+
+
+ EDM
+ hybrid
+ 4 5
+
+
+ Fifthmd_ext
+ hybrid
+ 10 11
+
+
+ Fifthpm_ext
+ hybrid
+ 8 9
+
+
+ _5rdmcp_ext
+ hybrid
+ 6 7
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 72.4
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.00394 -0.16652 0.03682
+ ulna
+
+
+ 0.00171 -0.17469 0.04049
+ ulna
+
+
+ 0.01076 -0.22783 0.03664
+ radius
+
+
+ 0.00388 -0.02234 0.01184
+ hand
+
+
+ 0.01693 -0.0564 0.01377
+ hand
+
+
+ 0.01735 -0.07692 0.00581
+ hand
+
+
+ 0.02765 -0.09314 -0.01511
+ hand
+
+
+ 0.02879 -0.09437 -0.02823
+ hand
+
+
+ 0.0287 -0.08524 -0.04295
+ hand
+
+
+ 0.02834 -0.07785 -0.05501
+ hand
+
+
+
+
+
+
+
+
+ Extensor_ellipse
+ hybrid
+ -1 -1
+
+
+ _2rdmcp_ext
+ hybrid
+ 5 6
+
+
+ Secondpm_ext
+ hybrid
+ 7 8
+
+
+ Secondmd_ext
+ hybrid
+ 9 10
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 47.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ -0.01412 -0.09706 0.02952
+ ulna
+
+
+ 0.00124 -0.13668 0.0227
+ radius
+
+
+ 0.02702 -0.21872 0.03828
+ radius
+
+
+ 0.03382 -0.22754 0.04607
+ radius
+
+
+ 0.04234 -0.23771 0.04173
+ radius
+
+
+ 0.02428 0.00014 0.00608
+ hand
+
+
+ 0.02338 -0.00917 -0.00039
+ hand
+
+
+ 0.02905 -0.01427 -0.00489
+ hand
+
+
+ 0.04414 -0.03417 -0.01814
+ hand
+
+
+ 0.04867 -0.04646 -0.02487
+ hand
+
+
+ 0.04751 -0.0701 -0.03774
+ hand
+
+
+ 0.04011 -0.07565 -0.04283
+ hand
+
+
+
+
+
+
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 88.3
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01924 -0.14695 0.02114
+ radius
+
+
+ 0.02276 -0.15857 0.02665
+ radius
+
+
+ 0.03831 -0.19722 0.03834
+ radius
+
+
+ 0.05235 -0.23611 0.02699
+ radius
+
+
+ 0.03123 0.00256 -0.00327
+ hand
+
+
+ 0.02972 -0.00794 -0.01436
+ hand
+
+
+ 0.04422 -0.033 -0.02422
+ hand
+
+
+ 0.04528 -0.04785 -0.03186
+ hand
+
+
+
+
+
+
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 46
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.00971 -0.09458 0.01769
+ radius
+
+
+ 0.01658 -0.13525 0.01915
+ radius
+
+
+ 0.01869 -0.17932 0.01988
+ radius
+
+
+ 0.038 -0.23171 0.0158
+ radius
+
+
+ 0.01869 0.00882 -0.01547
+ hand
+
+
+ -1.22173 0 1.22173
+ 0.01869 0.01869 0.01549
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ 0.00882 0.00882 -0.00078
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ -0.01547 -0.01547 -0.02087
+
+
+ flexion
+
+
+ 0.01244 -0.02207 -0.02089
+ hand
+
+
+ 0.01641 -0.02621 -0.02221
+ hand
+
+
+ 0.02457 -0.03294 -0.02237
+ hand
+
+
+ 0.02827 -0.05482 -0.03055
+ hand
+
+
+ 0.03511 -0.06519 -0.03749
+ hand
+
+
+ 0.03533 -0.07656 -0.04118
+ hand
+
+
+
+
+
+
+
+
+ FPL
+ hybrid
+ -1 -1
+
+
+ IPthumb
+ hybrid
+ 10 11
+
+
+ MPthumb
+ hybrid
+ -1 -1
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 201
+
+
+
+ false
+
+ 0
+
+ 1
+
+
+
+
+
+
+ 0.01154 -0.09477 0.01681
+ radius
+
+
+ 0.0303 -0.1397 0.03507
+ radius
+
+
+ 0.03993 -0.16072 0.034
+ radius
+
+
+ 0.04397 -0.17845 0.03134
+ radius
+
+
+ 0.05505 -0.23084 0.02368
+ radius
+
+
+ 0.03385 0.00634 -0.00745
+ hand
+
+
+ -1.22173 0 1.22173
+ 0.03385 0.03385 0.03135
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ 0.00634 0.00634 0.00534
+
+
+ flexion
+
+
+ -1.22173 0 1.22173
+ -0.00745 -0.00745 -0.01245
+
+
+ flexion
+
+
+ 0.02587 0.00205 -0.0165
+ hand
+
+
+ 0.02878 -0.00674 -0.0187
+ hand
+
+
+ 0.03076 -0.01583 -0.01885
+ hand
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ 1 1 1
+
+ 0 0 0 0 0 0
+
+ false
+
+ 4
+
+
+
+ 116.7
+
+
+
+
+
+
+
+
+
+ hand
+
+ 0.0266161 -0.0757448 -0.0576116
+
+ false
+
+
+
+
+
+
+
+
+
+
+
diff --git a/OpenSim/Tools/CMC_Joint.cpp b/OpenSim/Tools/CMC_Joint.cpp
index ccca23a329..5c629a558e 100644
--- a/OpenSim/Tools/CMC_Joint.cpp
+++ b/OpenSim/Tools/CMC_Joint.cpp
@@ -140,7 +140,7 @@ updateWorkVariables()
_q = 0;
if(_model) {
try {
- _q = &_model->updCoordinateSet().get(_coordinateName);
+ _q = &_model->getCoordinateSet().get(_coordinateName);
}
catch (const Exception&) {
throw Exception("CMC_Joint.updateWorkVariables: ERROR- joint task '" + getName()
@@ -191,7 +191,7 @@ operator=(const CMC_Joint &aTask)
* @param aModel Model.
*/
void CMC_Joint::
-setModel(Model& aModel)
+setModel(const Model& aModel)
{
CMC_Task::setModel(aModel);
updateWorkVariables();
diff --git a/OpenSim/Tools/CMC_Joint.h b/OpenSim/Tools/CMC_Joint.h
index 7ae51a6f9c..1063a3c8a3 100644
--- a/OpenSim/Tools/CMC_Joint.h
+++ b/OpenSim/Tools/CMC_Joint.h
@@ -62,7 +62,7 @@ OpenSim_DECLARE_CONCRETE_OBJECT(CMC_Joint, CMC_Task);
double &_limit;
// Work Variables
- Coordinate *_q;
+ const Coordinate *_q;
//=============================================================================
// METHODS
@@ -91,7 +91,7 @@ OpenSim_DECLARE_CONCRETE_OBJECT(CMC_Joint, CMC_Task);
//--------------------------------------------------------------------------
// GET AND SET
//--------------------------------------------------------------------------
- virtual void setModel(Model& aModel) override;
+ virtual void setModel(const Model& aModel) override;
void setCoordinateName(const std::string &aName);
std::string getCoordinateName() const;
double getLimit() const;
diff --git a/OpenSim/Tools/CMC_Orientation.cpp b/OpenSim/Tools/CMC_Orientation.cpp
index b31c079100..6a7964402a 100644
--- a/OpenSim/Tools/CMC_Orientation.cpp
+++ b/OpenSim/Tools/CMC_Orientation.cpp
@@ -90,7 +90,7 @@ setNull()
* Compute the Jacobian.
*/
void CMC_Orientation::
-computeJacobian()
+computeJacobian(const SimTK::State& s)
{
diff --git a/OpenSim/Tools/CMC_Orientation.h b/OpenSim/Tools/CMC_Orientation.h
index a20fdabc3b..1e79bb6c26 100644
--- a/OpenSim/Tools/CMC_Orientation.h
+++ b/OpenSim/Tools/CMC_Orientation.h
@@ -74,7 +74,7 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(CMC_Orientation, CMC_Task);
//--------------------------------------------------------------------------
// COMPUTATIONS
//--------------------------------------------------------------------------
- void computeJacobian() override;
+ void computeJacobian(const SimTK::State& s) override;
void computeEffectiveMassMatrix() override;
diff --git a/OpenSim/Tools/CMC_Point.cpp b/OpenSim/Tools/CMC_Point.cpp
index 5a60a8846f..2cda35947e 100644
--- a/OpenSim/Tools/CMC_Point.cpp
+++ b/OpenSim/Tools/CMC_Point.cpp
@@ -127,7 +127,7 @@ updateWorkVariables(const SimTK::State& s)
_v = 0;
if(_model) {
- BodySet& bs = _model->updBodySet();
+ const BodySet& bs = _model->getBodySet();
_model->getMultibodySystem().realize(s, SimTK::Stage::Velocity);
@@ -199,21 +199,6 @@ operator=(const CMC_Point &aTask)
// GET AND SET
//=============================================================================
//-----------------------------------------------------------------------------
-// MODEL
-//-----------------------------------------------------------------------------
-//_____________________________________________________________________________
-/**
- * Initializes pointers to the Coordinate and Speed in the model given the
- * coordinate name assigned to this task.
- *
- * @param aModel Model.
- */
-void CMC_Point::
-setModel(Model& aModel)
-{
- CMC_Task::setModel(aModel);
-}
-//-----------------------------------------------------------------------------
// Point
//-----------------------------------------------------------------------------
//_____________________________________________________________________________
@@ -265,7 +250,7 @@ computeErrors(const SimTK::State& s, double aT)
//std::cout<<"_inertialPTrk[2] = "<<_inertialPTrk[2]<updBodySet();
+ const BodySet& bs = _model->getBodySet();
_inertialPTrk = 0;
_inertialVTrk = 0;
@@ -430,7 +415,7 @@ computeAccelerations(const SimTK::State& s )
// ACCELERATION
_a = 0;
- BodySet& bs = _model->updBodySet();
+ const BodySet& bs = _model->getBodySet();
if(_wrtBodyName == "center_of_mass") {
SimTK::Vec3 pVec,vVec,aVec,com;
@@ -458,6 +443,74 @@ computeAccelerations(const SimTK::State& s )
}
}
+//_____________________________________________________________________________
+/**
+ * Compute the Jacobian for the tracked point given the current state
+ * of the model.
+ */
+void CMC_Point::
+computeJacobian(const SimTK::State& s )
+{
+ if (_wrtBodyName == "center_of_mass") {
+ double M = _model->getTotalMass(s);
+ SimTK::Matrix J(3, s.getNU(), 0.0);
+ for (int i = 0; i < _model->getBodySet().getSize(); i++) {
+ auto m = _model->getBodySet()[i].get_mass();
+ if (m == 0) {
+ cout << "Warning: body " << _model->getBodySet()[i].getName()
+ << " has zero mass" << endl;
+ continue;
+ }
+ auto com = _model->getBodySet()[i].get_mass_center();
+ SimTK::Matrix temp;
+ _model->getMatterSubsystem()
+ .calcStationJacobian(s,
+ _model->getBodySet()[i]
+ .getMobilizedBodyIndex(), com, temp);
+ J += m * temp;
+ }
+ _j = J / M;
+ } else {
+ _model->getMatterSubsystem()
+ .calcStationJacobian(s,
+ _model->getBodySet().get(_wrtBodyName)
+ .getMobilizedBodyIndex(), _point, _j);
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the Jacobian bias term for the tracked point given the current state
+ * of the model.
+ */
+void CMC_Point::
+computeBias(const SimTK::State& s )
+{
+ if (_wrtBodyName == "center_of_mass") {
+ double M = _model->getTotalMass(s);
+ SimTK::Vec3 JdotQdot(0);
+ for (int i = 0; i < _model->getBodySet().getSize(); i++) {
+ auto m = _model->getBodySet()[i].get_mass();
+ if (m == 0) {
+ cout << "Warning: body " << _model->getBodySet()[i].getName() <<
+ " has zero mass" << endl;
+ continue;
+ }
+ auto com = _model->getBodySet()[i].get_mass_center();
+ SimTK::Vec3 temp = _model->getMatterSubsystem().
+ calcBiasForStationJacobian(
+ s, _model->getBodySet()[i].getMobilizedBodyIndex(), com);
+ JdotQdot += m * temp;
+ }
+ _b = SimTK::Vector(-1.0 * JdotQdot / M);
+ } else {
+ SimTK::Vec3 JdotQdot = _model->getMatterSubsystem().
+ calcBiasForStationJacobian(
+ s, _model->getBodySet().get(_wrtBodyName).getMobilizedBodyIndex(), _point);
+ _b = SimTK::Vector(-1.0 * JdotQdot);
+ }
+}
+
//=============================================================================
// XML
//=============================================================================
diff --git a/OpenSim/Tools/CMC_Point.h b/OpenSim/Tools/CMC_Point.h
index 4bde65c385..aab620dd4f 100644
--- a/OpenSim/Tools/CMC_Point.h
+++ b/OpenSim/Tools/CMC_Point.h
@@ -61,7 +61,7 @@ OpenSim_DECLARE_CONCRETE_OBJECT(CMC_Point, CMC_Task);
// Work Variables
SimTK::Vec3 _p,_v,_inertialPTrk,_inertialVTrk;
- Body *_wrtBody,*_expressBody;
+ const Body *_wrtBody,*_expressBody;
//=============================================================================
// METHODS
@@ -90,7 +90,6 @@ OpenSim_DECLARE_CONCRETE_OBJECT(CMC_Point, CMC_Task);
//--------------------------------------------------------------------------
// GET AND SET
//--------------------------------------------------------------------------
- void setModel(Model& aModel) override;
void setPoint(const SimTK::Vec3 &aPoint);
SimTK::Vec3 getPoint() const;
@@ -101,6 +100,8 @@ OpenSim_DECLARE_CONCRETE_OBJECT(CMC_Point, CMC_Task);
void computeDesiredAccelerations(const SimTK::State& s, double aT) override;
void computeDesiredAccelerations(const SimTK::State& s, double aTI,double aTF) override;
void computeAccelerations(const SimTK::State& s ) override;
+ void computeJacobian(const SimTK::State& s) override;
+ void computeBias(const SimTK::State& s) override;
//--------------------------------------------------------------------------
// XML
diff --git a/OpenSim/Tools/CMC_Task.cpp b/OpenSim/Tools/CMC_Task.cpp
index 82f875a62a..f880481f7c 100644
--- a/OpenSim/Tools/CMC_Task.cpp
+++ b/OpenSim/Tools/CMC_Task.cpp
@@ -899,12 +899,24 @@ getAcceleration(int aWhich) const
* Compute the Jacobian.
*/
void CMC_Task::
-computeJacobian()
+computeJacobian(const SimTK::State& s)
{
log_error("CMC_Task::computeJacobian: This method should be overridden in "
"derived classes.");
}
+//_____________________________________________________________________________
+/**
+ * Compute the bias term for the Jacobian.
+ */
+void CMC_Task::
+computeBias(const SimTK::State& s)
+{
+ log_error("CMC_Task::computeBias: This method should be overridden in "
+ "derived classes.");
+}
+
+
//-----------------------------------------------------------------------------
// EFFECTIVE MASS MATRIX
//-----------------------------------------------------------------------------
diff --git a/OpenSim/Tools/CMC_Task.h b/OpenSim/Tools/CMC_Task.h
index ce40dd2aa4..97c20f4817 100644
--- a/OpenSim/Tools/CMC_Task.h
+++ b/OpenSim/Tools/CMC_Task.h
@@ -118,9 +118,11 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(CMC_Task, TrackingTask);
/** Accelerations. */
SimTK::Vec3 _a;
/** Jacobian. */
- double *_j;
+ SimTK::Matrix _j;
+ /** Jacobian bias. */
+ SimTK::Vector _b;
/** Effective mass matrix. */
- double *_m;
+ SimTK::Matrix _m;
//=============================================================================
// METHODS
@@ -204,6 +206,9 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(CMC_Task, TrackingTask);
double getDesiredAcceleration(int aWhich) const;
// ACCELERATIONS
double getAcceleration(int aWhich) const;
+ // JACOBIAN
+ SimTK::Matrix getJacobian() const;
+ SimTK::Vector getBias() const;
//--------------------------------------------------------------------------
// COMPUTATIONS
@@ -212,7 +217,8 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(CMC_Task, TrackingTask);
virtual void computeDesiredAccelerations(const SimTK::State& s, double aT) = 0;
virtual void computeDesiredAccelerations(const SimTK::State& s, double aTI,double aTF) = 0;
virtual void computeAccelerations(const SimTK::State& s ) = 0;
- virtual void computeJacobian();
+ virtual void computeJacobian(const SimTK::State& s);
+ virtual void computeBias(const SimTK::State& s);
virtual void computeEffectiveMassMatrix();
//=============================================================================
diff --git a/OpenSim/Tools/RegisterTypes_osimTools.cpp b/OpenSim/Tools/RegisterTypes_osimTools.cpp
index 6def930d80..8cbad4020d 100644
--- a/OpenSim/Tools/RegisterTypes_osimTools.cpp
+++ b/OpenSim/Tools/RegisterTypes_osimTools.cpp
@@ -55,6 +55,15 @@
#include "CorrectionController.h"
#include "MuscleStateTrackingTask.h"
+#include "TaskSpaceTorqueController.h"
+#include "TaskSpaceConstraintModel.h"
+#include "TaskSpaceTask.h"
+#include "TaskSpaceBodyTask.h"
+#include "TaskSpaceOrientationTask.h"
+#include "TaskSpaceStationTask.h"
+#include "TaskSpaceCoordinateTask.h"
+#include "TaskSpaceInertiaTask.h"
+
#include
#include
#include
@@ -103,6 +112,19 @@ OSIMTOOLS_API void RegisterTypes_osimTools()
Object::registerType( InverseKinematicsTool() );
Object::registerType( IMUInverseKinematicsTool());
Object::registerType( InverseDynamicsTool() );
+
+ Object::registerType( TaskSpaceTorqueController() );
+ Object::registerType( StationTask() );
+ Object::registerType( OrientationTask() );
+ Object::registerType( CoordinateTask() );
+ Object::registerType( OrientationTask() );
+ Object::registerType( InertiaTask() );
+ Object::registerType( NoConstraintModel() );
+ Object::registerType( DeSapioModel() );
+ Object::registerType( MistryModel() );
+ Object::registerType( SupportModel() );
+ Object::registerType( AghiliModel() );
+
// Old versions
Object::RenameType("rdCMC_Joint", "CMC_Joint");
Object::RenameType("rdCMC_Point", "CMC_Point");
diff --git a/OpenSim/Tools/TaskSpaceBodyTask.cpp b/OpenSim/Tools/TaskSpaceBodyTask.cpp
new file mode 100644
index 0000000000..7b1b3e472f
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceBodyTask.cpp
@@ -0,0 +1,104 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: BodyTask.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "TaskSpaceBodyTask.h"
+
+#include
+#include
+
+using namespace OpenSim;
+using namespace SimTK;
+using namespace std;
+
+BodyTask::BodyTask(){
+ constructProperties();
+ setNull();
+}
+
+void BodyTask::constructProperties() {
+ constructProperty_wrt_body("");
+ constructProperty_express_body("ground");
+ constructProperty_direction_vectors();
+ // Set default direction vectors
+ set_direction_vectors(0, SimTK::Vec3(1, 0, 0));
+ set_direction_vectors(1, SimTK::Vec3(0, 1, 0));
+ set_direction_vectors(2, SimTK::Vec3(0, 0, 1));
+
+ set_kp(Array(100, 3));
+ set_kv(Array(20, 3));
+ set_ka(Array(1, 3));
+ set_weight(Array(1, 3));
+}
+
+void BodyTask::copyData(const BodyTask& aTask) {
+
+ copyProperty_wrt_body(aTask);
+ copyProperty_express_body(aTask);
+ copyProperty_direction_vectors(aTask);
+}
+
+BodyTask& BodyTask::operator=(const BodyTask& aTask) {
+ // BASE CLASS
+ Object::operator=(aTask);
+
+ // DATA
+ copyData(aTask);
+
+ return (*this);
+}
+
+void BodyTask::setNull() {
+ setName(DEFAULT_NAME);
+
+ //_model = NULL;
+ _nTrk = 0;
+ _pErrLast = SimTK::Vector(Vec3(0.0));
+ _pErr = SimTK::Vector(Vec3(0.0));
+ _vErrLast = SimTK::Vector(Vec3(0.0));
+ _vErr = SimTK::Vector(Vec3(0.0));
+ _aDes = SimTK::Vector(Vec3(0.0));
+ _p = SimTK::Vector(Vec3(0.0));
+ _v = SimTK::Vector(Vec3(0.0));
+ _inertialPTrk = SimTK::Vector(Vec3(0.0));
+ _inertialVTrk = SimTK::Vector(Vec3(0.0));
+ _a = SimTK::Vector(Vec3(0.0));
+ _j = SimTK::Vector(Vec3(0.0));
+}
+
+void BodyTask::extendFinalizeFromProperties()
+{
+ Super::extendFinalizeFromProperties();
+}
+
+void BodyTask::extendConnectToModel(Model& aModel)
+{
+ Super::extendConnectToModel(aModel);
+}
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceBodyTask.h b/OpenSim/Tools/TaskSpaceBodyTask.h
new file mode 100644
index 0000000000..cad1dbf3a2
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceBodyTask.h
@@ -0,0 +1,100 @@
+#ifndef OPENSIM_TASK_SPACE_BODY_TASK_H_
+#define OPENSIM_TASK_SPACE_BODY_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: BodyTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "osimToolsDLL.h"
+#include "TaskSpaceTask.h"
+
+namespace OpenSim {
+
+/**
+ * \brief Tracking task associated with a body (e.g., position or orientation).
+ */
+class OSIMTOOLS_API BodyTask : public TaskSpaceTask {
+ OpenSim_DECLARE_ABSTRACT_OBJECT(BodyTask, TaskSpaceTask);
+
+public:
+ //=============================================================================
+ // PROPERTIES
+ //=============================================================================
+ OpenSim_DECLARE_PROPERTY(wrt_body, std::string,
+ "Name of body frame with respect to which a tracking objective is "
+ "specified. "
+ "The special name 'center_of_mass' refers to the system center of "
+ "mass. "
+ "This property is not used for tracking joint angles.");
+
+ OpenSim_DECLARE_PROPERTY(express_body, std::string,
+ "Name of body frame in which the tracking "
+ "objectives are expressed. This property is not used for tracking "
+ "joint angles.");
+
+ OpenSim_DECLARE_LIST_PROPERTY(direction_vectors, SimTK::Vec3,
+ "Direction vector[3] for each component of a task. "
+ "Joint tasks do not use this property.");
+
+ //=============================================================================
+ // PUBLIC METHODS
+ //=============================================================================
+
+ BodyTask();
+ virtual ~BodyTask() {}
+#ifndef SWIG
+ BodyTask& operator=(const BodyTask& aTaskObject);
+#endif
+
+ // virtual void computeErrors(const SimTK::State& s, double aT) = 0;
+ // virtual void computeDesiredAccelerations(
+ // const SimTK::State& s, double aT) = 0;
+ // virtual void computeDesiredAccelerations(
+ // const SimTK::State& s, double aTI, double aTF) = 0;
+ // virtual void computeAccelerations(const SimTK::State& s) = 0;
+ // virtual void computeJacobian(const SimTK::State& s);
+ // virtual void computeBias(const SimTK::State& s);
+ // virtual void update(const SimTK::State& s);
+
+protected:
+ // Model component interface.
+ void extendFinalizeFromProperties() override;
+ void extendConnectToModel(Model& model) override;
+
+private:
+ void constructProperties();
+ void setNull();
+ void copyData(const BodyTask& aTaskObject);
+
+//=============================================================================
+}; // end of class TaskSpaceBodyTask
+//=============================================================================
+} // end of namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_BODY_TASK_H_
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceComputeControlsEventHandler.h b/OpenSim/Tools/TaskSpaceComputeControlsEventHandler.h
new file mode 100644
index 0000000000..f62b3511bc
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceComputeControlsEventHandler.h
@@ -0,0 +1,66 @@
+
+#ifndef OPENSIM_TASK_SPACE_COMPUTE_CONTROLS_EVENT_HANDLER_H_
+#define OPENSIM_TASK_SPACE_COMPUTE_CONTROLS_EVENT_HANDLER_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceComputeControlsEventHandler.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "TaskSpaceTorqueController.h"
+
+#include "SimTKcommon.h"
+
+namespace OpenSim {
+
+class ComputeControlsEventHandler : public SimTK::PeriodicEventHandler
+ {
+ public:
+ ComputeControlsEventHandler( TaskSpaceTorqueController *controller) :
+ SimTK::PeriodicEventHandler(SimTK::Stage::Time),
+ _controller( controller ) {
+ }
+
+ void handleEvent (SimTK::State& s, SimTK::Real accuracy, bool& terminate) const override {
+ terminate = false;
+ _controller->computeControls( s, _controller->_tau);
+ _controller->setTargetTime(s.getTime() + _controller->getTargetDT());
+ }
+
+ SimTK::Real getNextEventTime( const SimTK::State& s, bool includeCurrent) const override {
+ if( _controller->getCheckTargetTime() ) {
+ return( _controller->getTargetTime() );
+ } else {
+ return( std::numeric_limits::infinity() );
+ }
+ }
+ TaskSpaceTorqueController* _controller;
+ };
+}
+
+#endif
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceConstraintModel.cpp b/OpenSim/Tools/TaskSpaceConstraintModel.cpp
new file mode 100644
index 0000000000..8946e0dc1f
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceConstraintModel.cpp
@@ -0,0 +1,341 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceConstraintModel.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer, and Dimitar *
+ * Stanev *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "TaskSpaceConstraintModel.h"
+
+#include "TaskSpaceUtilities.h"
+
+#include "OpenSim/Simulation/Model/SmoothSphereHalfSpaceForce.h"
+
+using namespace OpenSim;
+using namespace SimTK;
+
+namespace {
+ //TODO: convert to a test instead of running every time
+ static void validateConstraintData(const ConstraintData& data) {
+ if(data.M.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field M is empty."); }
+ if(data.MInv.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field MInv is empty."); }
+ if(data.McInv.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field McInv is empty."); }
+ if(data.NcT.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field NcT is empty."); }
+ if(data.bc.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field bc is empty."); }
+ if(data.Jc.nelt()==0) {
+ throw OpenSim::Exception("Error: ConstraintData field Jc is empty."); }
+ }
+
+ /**
+ * @brief wraps SimbodyMatterSubsystem's calcG (constraint matrix)
+ *
+ * @param s
+ * @param model
+ * @return Matrix
+ */
+ Matrix calcConstraintJacobian(const State& s, const Model& model) {
+ Matrix Jc;
+ model.getMatterSubsystem().calcG(s, Jc);
+ return Jc;
+ }
+
+ /**
+ * @brief wraps SimbodyMatterSubsystem's calcBiasForAccelerationConstraints()
+ *
+ * @param s
+ * @param model
+ * @return Vector
+ */
+ Vector calcConstraintBias(const State& s, const Model& model) {
+ // calcBiasForAccelerationConstraints assumes P *udot - bias = 0 we must
+ // invert the results so that P * udot = bias
+ Vector b;
+ model.getMatterSubsystem().calcBiasForAccelerationConstraints(s, b);
+ return -1.0 * b;
+ }
+
+ /**
+ * @brief calculates the support data for the constraint model, iterates over
+ * all the forces in the model and computes the center of pressure and the bias
+ * acceleration for each force.
+ *
+ * @param s
+ * @param model
+ * @return supportData
+ */
+ supportData calcSupportData(const State& s, const Model& model) {
+ supportData out;
+ out.bias_agg = Vector(s.getNU(), 0.0);
+
+ auto G = calcConstraintJacobian(s, model);
+ if (G.nelt() > 0) { // check constraints and break out early
+ log_debug("Constraints found in model. Contact forces will "
+ "NOT be used for support calculation.");
+ out.Js_agg = G;
+ out.M = calcM(s, model);
+ out.McInv = calcMInv(s, model);
+ Matrix LambdaInv = out.Js_agg * out.McInv * out.Js_agg.transpose();
+ Matrix Lambdac = FactorSVDPseudoinverse(LambdaInv);
+ auto PhiBarT = Lambdac * out.Js_agg * out.McInv;
+ out.bias_agg = calcConstraintBias(s, model);
+ out.NsT = 1 - out.Js_agg.transpose() * PhiBarT;
+ return out;
+ }
+
+ for (const auto& f : model.getComponentList()) {
+ if (f.getConcreteClassName() == "SmoothSphereHalfSpaceForce") {
+ auto& fc =
+ dynamic_cast(f);
+ auto b = fc.getConnectee("sphere")
+ .getFrame()
+ .getMobilizedBodyIndex();
+ OpenSim::Array f_ext = f.getRecordValues(s);
+ SimTK::Vec3 position =
+ fc.getConnectee("sphere").get_location();
+ SimTK::Vec3 location = fc.getConnectee("sphere")
+ .getFrame()
+ .getPositionInGround(s);
+ auto position_in_ground =
+ fc.getConnectee("sphere")
+ .getFrame()
+ .findStationLocationInGround(s, position);
+ if (out.cop.find(b) ==
+ out.cop.end()) { // init struct values to 0 at mat and
+ // compute frame jacobian
+ out.force[b] = SpatialVec(2);
+ out.force[b][0] = 0;
+ out.force[b][1] = 0;
+ out.cop[b] = Vec3(0.0);
+ out.Fs[b] = Matrix(6, 1, 0.0); // spatial
+ out.bias[b] =
+ Vector(out.Js[b].nrow(), 0.0); // task bias acceleration
+ out.bodies[b] = fc.getConnectee("sphere")
+ .getFrame()
+ .getMobilizedBody();
+ }
+
+ // Forces
+ out.force[b][1][0] += f_ext[6];
+ out.force[b][1][1] += f_ext[7];
+ out.force[b][1][2] += f_ext[8];
+
+ // Moments
+ out.force[b][0][0] += out.force[b][1][1] * position_in_ground[0]; // supposed to ignore the Y since the cop is on the floor
+ out.force[b][0][1] += 0;
+ out.force[b][0][2] +=
+ out.force[b][1][1] *
+ position_in_ground[2]; // supposed to ignore the Y since the
+ // cop is on the floor
+ }
+ }
+
+ double total_mass = 0.0;
+ for (auto it = out.cop.begin(); it != out.cop.end(); ++it)
+ { // loop over keys i map and update center of pressure
+ auto k = it->first; // keys are MobilizedBodyIndex
+ auto bod = out.bodies[k];
+ if (FlattenSpatialVec(out.force[k]).norm() > std::numeric_limits::epsilon()) {
+ out.cop[k][0] = out.force[k][0][0] / out.force[k][1][1]; // Mx / Fy
+ out.cop[k][1] = 0.0;
+ out.cop[k][2] = out.force[k][0][2] / out.force[k][1][1]; // Mz / Fy
+ out.cop[k] = out.cop[k] - bod.findStationLocationInGround(s, Vec3(0, 0, 0));
+ auto temp = FlattenSpatialVec(out.force[k]);
+ out.Fs[k] = temp;
+
+ out.Js[k] = calcFrameJacobian(s, model, k, out.cop[k]); // bod.getBodyOriginLocation(s)
+ out.Js[k] = out.Js[k].block(3, 0, 3, s.getNU());
+
+ auto bias = model.getMatterSubsystem().calcBiasForFrameJacobian(s, bod, out.cop[k]); // bod.getBodyOriginLocation(s)
+
+ out.bias[k] = -1.0 * FlattenSpatialVec(bias).getAsVector();
+
+ total_mass += bod.getBodyMass(s);
+
+ if (out.Js_agg.nelt() ==0) {
+ out.Js_agg = out.Js[k];
+ out.bias_agg = out.bias[k];
+ out.Fs_agg = out.Fs[k];
+ } else {
+ out.Js_agg = out.Js_agg + (bod.getBodyMass(s)) * out.Js[k];
+
+ out.Js_agg = concatenate(out.Js_agg, out.Js[k], 0);
+ out.bias_agg = concatenate(out.bias_agg, out.bias[k], 0).getAsVector();
+ out.Fs_agg = concatenate(out.Fs_agg, out.Fs[k], 0);
+ }
+ }
+ }
+
+ if (out.Js_agg.nelt() == 0) {
+ auto M = calcM(s, model);
+ out.M = M;
+ out.MInv = M.invert();
+ out.NsT = Matrix(s.getNU(), s.getNU());
+ out.NsT = 1.0;
+ out.Js_agg = Matrix(s.getNU(), s.getNU(), 0.0);
+ out.Js_agg = 0.0;
+ Matrix Mc = (out.NsT * M) + (1 - out.NsT);
+ out.Mc = Mc;
+ out.McInv = Mc.invert();
+ out.bias_agg = Vector(out.Js_agg.nrow(), 0.0);
+ out.Fs_agg = Vector(out.Js_agg.nrow(), 0.0);
+ return out;
+ }
+
+ out.MInv = calcMInv(s, model);
+ Matrix LambdaInv = out.Js_agg * out.MInv * out.Js_agg.transpose();
+ Matrix Lambdac = FactorSVDPseudoinverse(LambdaInv);
+ auto PhiBarT = Lambdac * out.Js_agg * out.MInv;
+ out.NsT = 1.0 - out.Js_agg.transpose() * PhiBarT;
+ auto M = calcM(s, model);
+ out.M = M;
+ Matrix Mc = (out.NsT * M) + 1.0 - out.NsT;
+ out.McInv = DampedSVDPseudoinverse(Mc);
+
+ return out;
+ }
+}
+
+/******************************************************************************/
+
+Matrix ConstraintModel::calcLambda(
+ const Matrix& Phi, const Matrix& MInv) const {
+ auto LambdaInv = Phi * MInv * ~Phi;
+ Matrix Lambda;
+ FactorSVD svd(LambdaInv);
+ svd.inverse(Lambda);
+ return Lambda;
+}
+
+/******************************************************************************/
+
+ConstraintData NoConstraintModel::calcConstraintData(const Model& model, const SimTK::State& s) const {
+
+ ConstraintData data;
+ data.Jc = Matrix(s.getNU(), s.getNU(), 0.0);
+ data.Jc = 1;
+ data.M = calcM(s, model);
+ data.MInv = calcMInv(s, model);
+ data.Mc = data.M;
+ data.McInv = data.MInv;
+ data.bc = Vector(s.getNU(), 0.0);
+ data.NcT = Matrix(s.getNU(), s.getNU());
+ data.NcT = 1;
+ validateConstraintData(data);
+ return data;
+}
+/******************************************************************************/
+
+ConstraintData DeSapioModel::calcConstraintData(const Model& model, const SimTK::State& s) const {
+
+ ConstraintData data;
+ data.M = calcM(s, model);
+ data.MInv = calcMInv(s, model);
+ // McInv
+ data.McInv = data.MInv;
+ // bc
+ data.Jc = calcConstraintJacobian(s, model);
+ auto JcT = ~data.Jc;
+ auto Lambdac = this->calcLambda(data.Jc, data.McInv);
+ auto b = calcConstraintBias(s, model);
+ // Stanev and Moustakas 2018, Eq 16
+ data.bc = -1.0 * JcT * Lambdac * b;
+ // NcT
+ auto JcBarT = Lambdac * data.Jc * data.McInv;
+ data.NcT = 1 - JcT * JcBarT;
+ validateConstraintData(data);
+ return data;
+}
+/******************************************************************************/
+
+ConstraintData AghiliModel::calcConstraintData(const Model& model, const SimTK::State& s) const {
+
+ ConstraintData data;
+ // NcT
+ data.Jc = calcConstraintJacobian(s, model);
+ Matrix JcInv;
+ FactorSVD JcSVD(data.Jc);
+ JcSVD.inverse(JcInv);
+ data.NcT = 1 - JcInv * data.Jc; // Nc^T = Nc due to MPP properties
+ // McInv
+ data.M = calcM(s, model);
+ data.MInv = calcMInv(s, model);
+ auto Ms = data.M + data.NcT * data.M - ~(data.NcT * data.M);
+ FactorSVD MsSVD(Ms);
+ MsSVD.inverse(data.McInv);
+ // bc
+ auto b = calcConstraintBias(s, model);
+ data.bc = -1.0 * data.M * JcInv * b;
+ validateConstraintData(data);
+ return data;
+}
+
+/******************************************************************************/
+
+ConstraintData MistryModel::calcConstraintData(const Model& model, const SimTK::State& s) const {
+
+ ConstraintData data;
+ Matrix Jc = calcConstraintJacobian(s, model);
+ Matrix Jcstar = FactorSVDPseudoinverse(Jc);
+ data.NcT = 1 - (Jcstar * Jc);
+ data.Jc = Jc;
+ data.M = calcM(s, model);
+ data.MInv = calcMInv(s, model);
+ Matrix Mc = (data.NcT * data.M) + (1 - data.NcT);
+ data.McInv = FactorSVDPseudoinverse(Mc);
+ data.bc = calcConstraintBias(s, model);
+ validateConstraintData(data);
+ return data;
+}
+
+/******************************************************************************/
+
+ConstraintData SupportModel::calcConstraintData(const Model& model, const SimTK::State& s) const {
+
+ ConstraintData data;
+ supportData out = calcSupportData(s, model);
+ data.Jc = out.Js_agg;
+ data.NcT = out.NsT;
+ data.M = out.M;
+ data.Mc = out.Mc;
+ data.MInv = out.MInv;
+ //TODO: This should be out.McInv (constraint consistent), but doing so conflicts with
+ // gait simulations since ground contact is treated as a constraint and given
+ // priority -1. This causes foot position tasks to be ineffective. Need to
+ // develop a workaround.
+ data.McInv = out.MInv;
+ Matrix JcPinv = FactorSVDPseudoinverse(data.Jc);
+ data.bc = JcPinv * out.bias_agg;
+ data.Fext = out.Fs_agg;
+ validateConstraintData(data);
+ return data;
+}
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceConstraintModel.h b/OpenSim/Tools/TaskSpaceConstraintModel.h
new file mode 100644
index 0000000000..821d8316cd
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceConstraintModel.h
@@ -0,0 +1,256 @@
+#ifndef OPENSIM_TASK_SPACE_CONSTRAINT_MODEL_H_
+#define OPENSIM_TASK_SPACE_CONSTRAINT_MODEL_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceConstraintModel.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer, and Dimitar *
+ * Stanev *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "osimToolsDLL.h"
+#include "OpenSim/Common/Object.h"
+#include "OpenSim/Simulation/Model/Model.h"
+
+namespace OpenSim {
+
+//================================================================================
+// DATA STRUCTURES
+//================================================================================
+
+/** \brief Calculated by calcConstraintData(). */
+struct ConstraintData {
+ /** System mass matrix.*/
+ SimTK::Matrix M;
+ /** Inverse of system mass matrix.*/
+ SimTK::Matrix MInv;
+ /** Constraint-consistent inertia mass matrix.*/
+ SimTK::Matrix Mc;
+ /** Inverse of constraint-consistent inertia mass matrix.*/
+ SimTK::Matrix McInv;
+ /** Transpose of the constraint nullspace matrix. */
+ SimTK::Matrix NcT;
+ /** Constraint bias term. */
+ SimTK::Vector bc;
+ /** Constraint Jacobian. */
+ SimTK::Matrix Jc;
+ /** External forces. */
+ SimTK::Matrix Fext;
+};
+
+struct supportData {
+ SimTK::Matrix Js_agg; //!<@brief aggregate support jacobian
+ SimTK::Matrix Vb_agg; //!<@brief aggregate transformation Matrix
+ SimTK::Matrix M; //!<@brief mass matrix
+ SimTK::Matrix MInv; //!<@brief inverse mass matrix
+ SimTK::Matrix Mc; //!<@brief support consistent mass matrix
+ SimTK::Matrix McInv; //!<@brief support consistent inverse mass matrix
+ SimTK::Matrix
+ NsT; //!<@brief support consistent Nullspace for support tasks
+ SimTK::Matrix Fs_agg; //!<@brief Aggregate support force (applied to
+ //!< centers of pressure)
+ SimTK::Vector bias_agg; //!<@brief aggregate bias force (mapping external
+ //!< loads task to bias accel)
+ std::map
+ Js; //!<@brief support jacobian (6xnt)
+ std::map
+ Vb; //!<@brief Support Transformation Matrix
+ std::map
+ Fs; //!<@brief support force (spatial (6x1))
+ std::map
+ cop; //!<@brief center of pressure (3x1)
+ std::map
+ force; //!<@brief linear summed cop force and resultant moment
+ //!<(3x2)
+ std::map
+ bias; //!<@brief task bias accel (6x1)
+ std::map
+ bodies; //!<@brief task bias accel (6x1)
+};
+
+//================================================================================
+// CONSTRAINT MODELS
+//================================================================================
+//_____________________________________________________________________________
+/**
+ * \brief An abstract class for defining constraint models.
+ */
+class ConstraintModel : public ModelComponent {
+ OpenSim_DECLARE_ABSTRACT_OBJECT(ConstraintModel, ModelComponent);
+
+public:
+ /**
+ * Calculates the constraint data. Note that in the future additional
+ * ConstraintData may be provided.
+ */
+ virtual ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const = 0;
+protected:
+ SimTK::Matrix calcLambda(
+ const SimTK::Matrix& Phi, const SimTK::Matrix& MInv) const;
+};
+
+//_____________________________________________________________________________
+/**
+ * \brief This model assumes that there are no constraints.
+ *
+ * \f$ M \ddot{q} + f = \tau \f$
+ *
+ * \f$ M_c^{-1} = M^{-1}, \; b_c = 0, \; N_c^T = 1 \f$
+ */
+class OSIMTOOLS_API NoConstraintModel : public ConstraintModel {
+ OpenSim_DECLARE_CONCRETE_OBJECT(NoConstraintModel, ConstraintModel);
+
+public:
+ ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const override;
+};
+
+//_____________________________________________________________________________
+/**
+ * \brief This model uses the inertia weighted generalized inverse of the
+ * constraint Jacobian as adopted by De Sapio et al. [1] to derive the
+ * constrained representation of the equations of motion.
+ *
+ * \f$ M \ddot{q} + f + \Phi^T \lambda = \tau \f$ (1)
+ *
+ * \f$ \Phi \ddot{q} = b \f$ (2)
+ *
+ * @see Utilities.h
+ *
+ * The goal is to decouple constraint and applied forces through coordinate
+ * projection. Multiply Eq. (1) from the left by \f$ \Phi M^{-1} \f$,
+ * making use of Eq. (2) and solve for \f$ \lambda \f$
+ *
+ * \f$ b + \Phi M^{-1} f + \Phi M^{-1} \Phi^T \lambda = \Phi M^{-1} \tau
+ * \f$
+ *
+ * \f$ \lambda = \bar{\Phi}^T (\tau - f) - \Lambda_c b, ;\ \Lambda_c = (\Phi
+ * M^{-1} \Phi^T)^{-1}, \; \bar{\Phi}^T = \Lambda_c \Phi M^{-1} \f$ (3)
+ *
+ * Then combine Eqs. (1) and (3)
+ *
+ * \f$ M \ddot{q} + f^{\perp} + bc = \tau^{\perp} \f$
+ *
+ * \f$ b_c = - \Phi^T \Lambda_c b \f$
+ *
+ * \f$ f^{\perp} = N_c^T f, \; \tau^{\perp} = N_c^T \tau, \; N_c^T = 1 -
+ * \Phi^T \bar{\Phi}^T \f$
+ *
+ * [1] De Sapio, V., & Park, J. (2010). Multitask Constrained Motion
+ * Control Using a Mass-Weighted Orthogonal Decomposition. Journal of
+ * Applied Mechanics, 77(4), 1–9. https://doi.org/10.1115/1.4000907
+ */
+class OSIMTOOLS_API DeSapioModel : public ConstraintModel {
+ OpenSim_DECLARE_CONCRETE_OBJECT(DeSapioModel, ConstraintModel);
+
+public:
+ ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const override;
+};
+
+//_____________________________________________________________________________
+/**
+ * \brief This model make uses of the Moore - Penrose pseudoinverse (MPP)
+ * and the theory of linear projection operators to decouple the constraint
+ * and applied forces based on Aghili [1].
+ *
+ * \f$ M \ddot{q} + f + \Phi^T \lambda = \tau \f$ (1)
+ *
+ * \f$ \Phi \ddot{q} = b \f$ (2)
+ *
+ * \f$ N_c = N_c^T = I - \Phi^+ \Phi \f$ (3)
+ *
+ * Reexpress Eqs. (1) and (2) using (3)
+ *
+ * \f$ N_c M \ddot{q} + N_c f = N_c \tau, \; N_c \Phi^T = 0 \f$
+ * (4)
+ * \f$ \ddot{q}_{\parallel} = M (I - N_c) \ddot{q} = \Phi^+ b \f$
+ *
+ * Combining Eqs. (4) together we can derive the model
+ *
+ * \f$ M^{'} \ddot{q} + f_{perp} + b_c = \tau_{\perp} \f$
+ *
+ * \f$ M^{'} = M + N_c M - (N_c M)^T \f$
+ *
+ * \f$ f^{\perp} = N_c f, \; \tau^{\perp} = N_c \tau \f$
+ *
+ * \f$ b_c = -M \Phi^+ b \f$
+ *
+ * [1] Aghili, F. (2005). A unified approach for inverse and direct
+ * dynamics of constrained multibody systems based on linear projection
+ * operator: Applications to control and simulation. IEEE Transactions on
+ * Robotics, 21(5), 834–849. https://doi.org/10.1109/TRO.2005.851380
+ */
+class OSIMTOOLS_API AghiliModel : public ConstraintModel {
+ OpenSim_DECLARE_CONCRETE_OBJECT(AghiliModel, ConstraintModel);
+
+public:
+ ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const override;
+};
+
+//_____________________________________________________________________________
+/**
+ * \brief This model make use of the augmented Jacobian methods for task
+ * prioritization based on Mistry [4]. Requires external contact with the
+ * environment to be modeled using kinematic constraints.
+ *
+ * [4] Mistry, Michael & Nakanishi, Jun & Schaal, Stefan. (2007). Task space
+ * control with prioritization for balance and locomotion.
+ * 331-338. 10.1109/IROS.2007.4399595.
+ */
+class OSIMTOOLS_API MistryModel : public ConstraintModel {
+ OpenSim_DECLARE_CONCRETE_OBJECT(MistryModel, ConstraintModel);
+
+public:
+ ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const override;
+};
+
+//_____________________________________________________________________________
+/**
+ * \brief Computes support-consistent constraint data for models which use
+ * contact objects to model interaction with the environment. The center of
+ * pressure is calculated for each body in contact with the environment, then
+ * constraint data is calculated as if there were a weld constraint at the
+ * location of the center of pressure. This model utilizes this the support
+ * consistent formulation from Sentis 2007 [1].
+ *
+ * [1] Sentis, L. (2007). Synthesis and Control of Whole-Body
+ * Behaviors in Humanoid Systems. Stanford University. Retrieved from
+ * http://dl.acm.org/citation.cfm?id=1354211
+ *
+ * * @see Utilities.h
+ *
+ * * @see ConstraintModel.h
+ *
+ * */
+class OSIMTOOLS_API SupportModel : public ConstraintModel {
+ OpenSim_DECLARE_CONCRETE_OBJECT(SupportModel, ConstraintModel);
+
+public:
+ ConstraintData calcConstraintData(const Model& model, const SimTK::State& s) const override;
+};
+} // END namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_CONSTRAINT_MODEL_H_
diff --git a/OpenSim/Tools/TaskSpaceCoordinateTask.cpp b/OpenSim/Tools/TaskSpaceCoordinateTask.cpp
new file mode 100644
index 0000000000..cb95d18ec9
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceCoordinateTask.cpp
@@ -0,0 +1,423 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceCoordinateTask.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//=============================================================================
+// INCLUDES
+//=============================================================================
+#include "OpenSim/Simulation/Model/Model.h"
+#include "TaskSpaceCoordinateTask.h"
+
+using namespace std;
+using namespace SimTK;
+using namespace OpenSim;
+
+//=============================================================================
+// STATICS
+//=============================================================================
+
+//=============================================================================
+// CONSTRUCTOR(S) AND DESTRUCTOR
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Destructor.
+ */
+CoordinateTask::~CoordinateTask() {}
+
+//_____________________________________________________________________________
+/**
+ * Construct a task for a specified generalized coordinate.
+ *
+ * @param aQID ID of the generalized coordinate to be tracked.
+ * @todo Instead of an integer id, the name of the coordinate
+ * should be used.
+ */
+CoordinateTask::CoordinateTask(
+ const std::string& aCoordinateName, bool limit_avoidance)
+ : TaskSpaceTask() {
+ setupProperties();
+ setNull();
+ set_coordinate(aCoordinateName);
+ setName(aCoordinateName + "Task");
+ set_limit_avoidance(limit_avoidance);
+
+}
+
+//_____________________________________________________________________________
+/**
+ * Copy constructor.
+ *
+ * @param aTask Joint task to be copied.
+ */
+CoordinateTask::CoordinateTask(const CoordinateTask& aTask)
+ : TaskSpaceTask(aTask) {
+ setNull();
+ copyData(aTask);
+}
+
+//=============================================================================
+// CONSTRUCTION
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Set NULL values for all member variables.
+ */
+void CoordinateTask::setNull() {
+ _nTrk = 1;
+ _q = NULL;
+ _p = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _v = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _inertialPTrk = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _inertialVTrk = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _pErrLast = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _pErr = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _vErrLast = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _vErr = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _aDes = SimTK::Vector(SimTK::Vector(1, 0.0));
+ _a = SimTK::Vector(SimTK::Vector(1, 0.0));
+}
+//_____________________________________________________________________________
+/**
+ * @brief Set up serialized member variables.
+ *
+ * @param aCoordinateName Name of the coordinate to be tracked.
+ */
+void CoordinateTask::setupProperties() {
+ //Construct properties unique to CoordinateTask
+ constructProperty_limit_avoidance(false);
+ constructProperty_coordinate("");
+
+ //Set inherited properties
+ setName("CoordTask");
+ // Set default gains and weight
+ set_kp(Array(100, 1));
+ set_kv(Array(20, 1));
+ set_ka(Array(1, 1));
+ set_weight(Array(1, 1));
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Copy data members from one CoordinateTask to another.
+ *
+ * @param aTask CoordinateTask to be copied.
+ */
+void CoordinateTask::copyData(const CoordinateTask& aTask)
+{
+ copyProperty_coordinate(aTask);
+ copyProperty_limit_avoidance(aTask);
+
+ updateWorkVariables();
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Update the work variables based on the current model.
+ * This method is called by setModel() and setCoordinateName().
+ *
+ *
+ */
+void CoordinateTask::updateWorkVariables() {
+ _q = NULL;
+ if (hasModel()) {
+ try {
+ int nv = getModel().getWorkingState().getNU();
+ _q = &getModel().getCoordinateSet().get(get_coordinate());
+ //Set the Jacobian entry corresponding to this coordinate to 1.0
+ int _mbti = getModel()
+ .getMatterSubsystem()
+ .getMobilizedBody(_q->getBodyIndex())
+ .getFirstUIndex(getModel().getWorkingState()) +
+ _q->getMobilizerQIndex();
+ _j = SimTK::Matrix(1, nv, 0.0);
+ _j(0, _mbti) = 1.0;
+ _b = SimTK::Vector(1, 0.0);
+ } catch (...) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "CoordinateTask.updateWorkVariables: ERROR- joint task references invalid coordinate");
+ }
+ }
+}
+
+//=============================================================================
+// OPERATORS
+//=============================================================================
+//-----------------------------------------------------------------------------
+// ASSIGNMENT
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Assignment operator.
+ *
+ * @param aTask Object to be copied.
+ * @return Reference to the altered object.
+ */
+CoordinateTask& CoordinateTask::operator=(const CoordinateTask& aTask) {
+ // BASE CLASS
+ TaskSpaceTask::operator=(aTask);
+
+ // DATA
+ copyData(aTask);
+
+ return (*this);
+}
+
+//=============================================================================
+// COMPUTATIONS
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Compute the position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void CoordinateTask::computeErrors(const SimTK::State& s, double aT) {
+ if (get_limit_avoidance() == true) {
+ _pErr[0] =
+ (0.5 * (_q->getRangeMax() - _q->getRangeMin()) -
+ _q->getValue(s));
+ } else {
+ _pErr[0] = (get_position_functions(0).calcValue(SimTK::Vector(1, aT)) -
+ _q->getValue(s));
+ }
+
+ if (getProperty_velocity_functions().size() == 0) {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ if (get_limit_avoidance() == true) {
+ _vErr[0] = (0.0 - _q->getSpeedValue(s));
+ } else {
+ _vErr[0] = (get_position_functions(0).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT)) -
+ _q->getSpeedValue(s));
+ }
+ } else {
+ if (get_limit_avoidance() == true) {
+ _vErr[0] = (0.0 - _q->getSpeedValue(s));
+ } else {
+ _vErr[0] = (get_velocity_functions(0).calcValue(
+ SimTK::Vector(1, aT)) -
+ _q->getSpeedValue(s));
+ }
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aT Time at which the desired accelerations are to be computed in
+ * real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void CoordinateTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aT) {
+ computeDesiredAccelerations(s, aT, aT);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void CoordinateTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) {
+ double a;
+ // CHECK
+ if (!hasModel()) {
+ log_warn("CoordinateTask model not set.");
+ return;
+ }
+ if (getProperty_position_functions().size() == 0) {
+ log_warn("CoordinateTask position tracking function not set.");
+ return;
+ }
+ if (_q == NULL) {
+ updateWorkVariables();
+ return;
+ }
+ _a = SimTK::Vector(1, 0.0);
+ _aDes = SimTK::Vector(1, 0.0);
+ checkFunctions();
+
+ // COMPUTE ERRORS
+ computeErrors(s, aTI);
+
+ // DESIRED ACCELERATION
+ double p = get_kp(0) * _pErr[0];
+ double v = get_kv(0) * _vErr[0];
+ if (getProperty_acceleration_functions().size() == 0) {
+ std::vector derivComponents(2);
+ derivComponents[0] = 0;
+ derivComponents[1] = 0;
+ a = get_ka(0) * get_position_functions(0).calcDerivative(
+ derivComponents, SimTK::Vector(1, aTF));
+ } else {
+ a = get_ka(0) *
+ get_acceleration_functions(0).calcValue(SimTK::Vector(1, aTF));
+ }
+ _aDes[0] = get_weight(0) * (a + v + p);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the acceleration of the appropriate generalized coordinate.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * For joints (i.e., generalized coordinates), the acceleration is
+ * not computed. It has already been computed and is simply retrieved
+ * from the model.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+void CoordinateTask::computeAccelerations(const SimTK::State& s) {
+ _a = SimTK::NaN;
+ // CHECK
+ if (!hasModel()) return;
+
+ _a = SimTK::Vector(1, 1.0);
+ // ACCELERATION
+ _a[0] = _q->getAccelerationValue(s);
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the Jacobian, since the task is already in coordinate space,
+ * the jacobian is nu x 1 identity with 1 in the column of the specified
+ * coordinate. When considering joint limit avoidance, the expression for J is
+ * based on the potential field expression.
+ * @param s current state
+ * @return SimTK::Matrix Jacobian
+ * @see CoordinateTask::computeJointLimitMatrix(const SimTK::State& s)
+ *
+ */
+void CoordinateTask::computeJacobian(const SimTK::State& s) {
+ SimTK::Matrix J(1, s.getNU(), 0.0);
+ auto& matter = getModel().getMatterSubsystem();
+ int _mbti = matter.getMobilizedBody(_q->getBodyIndex()).getFirstUIndex(s) +
+ _q->getMobilizerQIndex();
+ if (get_limit_avoidance() == true) { // use the potential field expression
+ // if we care about limit avoidance.
+ double max = _q->getRangeMax();
+ double min = _q->getRangeMin();
+ double buffer = (max - min) * .10;
+ double minbuf = min + buffer;
+ double maxbuf = max - buffer;
+ double val = _q->getValue(s);
+ if (val <= minbuf) {
+ J(0, _mbti) = 1.0 * (1.0 - computeJointLimitMatrix(s));
+ } else if (val >= maxbuf) {
+ J(0, _mbti) = 1.0 * (1.0 - computeJointLimitMatrix(s));
+ }
+ } else {
+ J(0, _mbti) = 1.0;
+ }
+ _j = J;
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the joint limit matrix, which is used in the potential field
+ * expression for the Jacobian.
+ *
+ * @see CoordinateTask::computeJointLimitMatrix(const SimTK::State& s)
+ */
+double CoordinateTask::computeJointLimitMatrix(const SimTK::State& s) {
+ double JL = 0.0;
+ double max, min, buffer, minbuf, maxbuf, val, deltaH = 0.0;
+ max = _q->getRangeMax();
+ min = _q->getRangeMin();
+ buffer = (max - min) * .10;
+ minbuf = min + buffer;
+ maxbuf = max - buffer;
+ val = _q->getValue(s);
+ if (val <= min) {
+ JL = 1.0;
+ } else if ((val > min) && (val < minbuf)) {
+ JL = 0.5 + 0.5 * sin((Pi / buffer) * (val - minbuf) + Pi / 2);
+ } else if ((val <= maxbuf) && (val >= minbuf)) {
+ JL = 0.0;
+ } else if ((val > maxbuf) && (val < max)) {
+ JL = 0.5 + 0.5 * sin((Pi / buffer) * (val - maxbuf) - Pi / 2);
+ } else if (val >= max) {
+ JL = 1.0;
+ }
+ return JL;
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the Jacobian bias term for the tracked point given the current
+ * state of the model.
+ *
+ * @param s current state
+ * @return SimTK::Vector bias term
+ * @see CoordinateTask::computeJointLimitBias(const SimTK::State& s)
+ */
+void CoordinateTask::computeBias(const SimTK::State& s) {
+ if (_q == NULL) { updateWorkVariables(); }
+
+ SimTK::SpatialVec jdu =
+ getModel().getMatterSubsystem().calcBiasForFrameJacobian(s,
+ _q->getJoint().getParentFrame().getMobilizedBodyIndex(),
+ SimTK::Vec3(0));
+ // Jdot*u is 0, because Jdot is zero. [0 ... 1 .. 0] * u = 0
+ _b = SimTK::Vector(1,0.0 * jdu[0][_q->getMobilizerQIndex()]);
+}
+
+//=============================================================================
+// XML
+//=============================================================================
+//-----------------------------------------------------------------------------
+// UPDATE FROM XML NODE
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Update this object based on its XML node.
+ *
+ * @param aDeep If true, update this object and all its child objects
+ * (that is, member variables that are Object's); if false, update only
+ * the member variables that are not Object's.
+ */
+void CoordinateTask::updateFromXMLNode(
+ SimTK::Xml::Element& aNode, int versionNumber) {
+ Super::updateFromXMLNode(aNode, versionNumber);
+}
diff --git a/OpenSim/Tools/TaskSpaceCoordinateTask.h b/OpenSim/Tools/TaskSpaceCoordinateTask.h
new file mode 100644
index 0000000000..173eee2385
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceCoordinateTask.h
@@ -0,0 +1,254 @@
+#ifndef OPENSIM_TASK_SPACE_COORDINATE_TASK_H_
+#define OPENSIM_TASK_SPACE_COORDINATE_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceCoordinateTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//============================================================================
+// INCLUDE
+//============================================================================
+#include "osimToolsDLL.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Common/PropertyDbl.h"
+#include "TaskSpaceTask.h"
+
+namespace OpenSim {
+
+class Coordinate;
+
+//=============================================================================
+//=============================================================================
+/**
+ * A class for specifying the tracking task for a joint.
+ */
+class OSIMTOOLS_API CoordinateTask : public TaskSpaceTask {
+ OpenSim_DECLARE_CONCRETE_OBJECT(CoordinateTask, TaskSpaceTask);
+//==========================================================================
+// DATA
+//==========================================================================
+public:
+
+ OpenSim_DECLARE_PROPERTY(coordinate, std::string,
+ "Name of coordinate with respect to which a tracking objective is "
+ "specified. ");
+
+ OpenSim_DECLARE_PROPERTY(limit_avoidance, bool,
+ "Boolean to indicate whether this coordinate should be used for "
+ "limit avoidance (true) or coordinate space control (false).");
+
+protected:
+ // Work Variables
+ const OpenSim::Coordinate* _q;
+ mutable int _mbti;
+
+ //==========================================================================
+ // METHODS
+ //==========================================================================
+ //--------------------------------------------------------------------------
+ // CONSTRUCTION
+ //--------------------------------------------------------------------------
+public:
+ /**
+ * Construct a task for a specified generalized coordinate.
+ *
+ * @param aQID ID of the generalized coordinate to be tracked.
+ * @todo Instead of an integer id, the name of the coordinate
+ * should be used.
+ */
+ CoordinateTask(const std::string& aCoordinateName = "",
+ bool limit_avoidance = false);
+
+ /**
+ * Copy constructor.
+ *
+ * @param aTask Joint task to be copied.
+ */
+ CoordinateTask(const CoordinateTask& aTask);
+
+ /**
+ * Destructor.
+ */
+ virtual ~CoordinateTask();
+
+ //--------------------------------------------------------------------------
+ // GET AND SET
+ //--------------------------------------------------------------------------
+ /**
+ * @brief Set the limit avoidance flag
+ *
+ * @param b flag to set
+ */
+ void setLimitAvoidance(const bool b) { set_limit_avoidance(b); }
+
+ //--------------------------------------------------------------------------
+ // COMPUTATIONS
+ //--------------------------------------------------------------------------
+ /**
+ * Compute the position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeErrors(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aT Time at which the desired accelerations are to be computed in
+ * real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeDesiredAccelerations(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) override;
+
+ /**
+ * Compute the acceleration of the appropriate generalized coordinate.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * For joints (i.e., generalized coordinates), the acceleration is
+ * not computed. It has already been computed and is simply retrieved
+ * from the model.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+ void computeAccelerations(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the Jacobian, since the task is already in coordinate
+ * space, the jacobian is nu x 1 identity with 1 in the column of the
+ * specified coordinate. When considering joint limit avoidance, the
+ * expression for J is based on the potential field expression.
+ * @param s current state
+ * @return SimTK::Matrix Jacobian
+ * @see CoordinateTask::computeJointLimitMatrix(const SimTK::State& s)
+ *
+ */
+ void computeJacobian(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the Jacobian bias term for the tracked point given the
+ * current state of the model.
+ *
+ * @param s current state
+ * @return SimTK::Vector bias term
+ * @see CoordinateTask::computeJointLimitBias(const SimTK::State& s)
+ */
+ void computeBias(const SimTK::State& s) override;
+
+ /**
+ * @brief Update internal storage of task dynamics.
+ *
+ * @param s current state
+ */
+ // void update(const SimTK::State& s) override;
+
+ /**
+ * Compute the joint limit matrix, which is used in the potential field
+ * expression for the Jacobian.
+ *
+ * @see CoordinateTask::computeJointLimitMatrix(const SimTK::State& s)
+ */
+ double computeJointLimitMatrix(const SimTK::State& s);
+
+ //--------------------------------------------------------------------------
+ // XML
+ //--------------------------------------------------------------------------
+ /**
+ * Update this object based on its XML node.
+ *
+ * @param aDeep If true, update this object and all its child objects
+ * (that is, member variables that are Object's); if false, update only
+ * the member variables that are not Object's.
+ */
+ void updateFromXMLNode(
+ SimTK::Xml::Element& aNode, int versionNumber = -1) override;
+#ifndef SWIG
+ /**
+ * Assignment operator.
+ *
+ * @param aTask Object to be copied.
+ * @return Reference to the altered object.
+ */
+ CoordinateTask& operator=(const CoordinateTask& aTask);
+#endif
+
+private:
+ /**
+ * Set NULL values for all member variables.
+ */
+ void setNull();
+
+ /**
+ * @brief Set up serialized member variables.
+ *
+ * @param aCoordinateName Name of the coordinate to be tracked.
+ */
+ void setupProperties();
+
+ /**
+ * @brief Copy data members from one CoordinateTask to another.
+ *
+ * @param aTask CoordinateTask to be copied.
+ */
+ void copyData(const CoordinateTask& aTask);
+
+ /**
+ * @brief Update the work variables based on the current model.
+ * This method is called by setModel() and setCoordinateName().
+ */
+ void updateWorkVariables();
+
+ //--------------------------------------------------------------------------
+ // OPERATORS
+ //--------------------------------------------------------------------------
+
+//==========================================================================
+}; // END of class CoordinateTask
+//==========================================================================
+}; // namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_COORDINATE_TASK_H_
diff --git a/OpenSim/Tools/TaskSpaceInertiaTask.cpp b/OpenSim/Tools/TaskSpaceInertiaTask.cpp
new file mode 100644
index 0000000000..c2f5d9ca3e
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceInertiaTask.cpp
@@ -0,0 +1,373 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceInertiaTask.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//=============================================================================
+// INCLUDES
+//=============================================================================
+#include "OpenSim/Simulation/Model/Model.h"
+#include "TaskSpaceInertiaTask.h"
+
+using namespace OpenSim;
+using SimTK::Vec3;
+using SimTK::Vector;
+
+//=============================================================================
+// STATICS
+//=============================================================================
+
+//=============================================================================
+// CONSTRUCTOR(S) AND DESTRUCTOR
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Destructor.
+ */
+InertiaTask::~InertiaTask() {}
+//_____________________________________________________________________________
+/**
+ * Default constructor.
+ */
+InertiaTask::InertiaTask() {
+ setupProperties();
+ setNull();
+}
+
+//_____________________________________________________________________________
+/**
+ * Copy constructor.
+ */
+InertiaTask::InertiaTask(const InertiaTask& aTask) : BodyTask(aTask) {
+ setNull();
+}
+
+//=============================================================================
+// CONSTRUCTION
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Set NULL values for all member variables.
+ */
+void InertiaTask::setNull() {
+ _nTrk = 3;
+ _p = SimTK::Vector(Vec3(0.0));
+ _v = SimTK::Vector(Vec3(0.0));
+ _inertialPTrk = SimTK::Vector(Vec3(0.0));
+ _inertialVTrk = SimTK::Vector(Vec3(0.0));
+ _pErrLast = Vector(Vec3(0.0));
+ _pErr = Vector(Vec3(0.0));
+ _vErrLast = Vector(Vec3(0.0));
+ _vErr = Vector(Vec3(0.0));
+ _aDes = Vector(Vec3(0.0));
+ _a = Vector(Vec3(0.0));
+}
+
+void InertiaTask::setupProperties() {
+ // Set default direction vectors
+ set_direction_vectors(0, SimTK::Vec3(1, 0, 0));
+ set_direction_vectors(1, SimTK::Vec3(0, 1, 0));
+ set_direction_vectors(2, SimTK::Vec3(0, 0, 1));
+ setName("InertiaTask");
+ // Set default gains
+ set_kp(Array(100, 3));
+ set_kv(Array(20, 3));
+ set_ka(Array(1, 3));
+}
+// void InertiaTask::setTaskFunctions(int i, Function* aF0) {
+// if (aF0 != NULL) set_position_functions(i, *aF0);
+// }
+
+//_____________________________________________________________________________
+/**
+ * Update work variables
+ */
+void InertiaTask::updateWorkVariables(const SimTK::State& s) {
+ _p = 0;
+ _v = 0;
+ if (hasModel()) {
+ const BodySet& bs = getModel().getBodySet();
+
+ if (s.getSystemStage() < SimTK::Stage::Velocity) {
+ getModel().getMultibodySystem().realize(s, SimTK::Stage::Velocity);
+ }
+
+ SimTK::Vec3 pVec, vVec;
+ double Mass = 0.0;
+ _p = Vector(getModel()
+ .getMatterSubsystem()
+ .calcSystemCentralMomentum(s)
+ .get(0));
+ _v = Vector(getModel()
+ .getMatterSubsystem()
+ .calcSystemCentralMomentum(s)
+ .get(0));
+ // COMPUTE COM OF WHOLE BODY
+ if (_v[0] != _v[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid velocity components");
+ }
+
+ if (_p[0] != _p[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid position components");
+ }
+
+ }
+}
+
+//=============================================================================
+// COMPUTATIONS
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Compute the angular position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void InertiaTask::computeErrors(const SimTK::State& s, double aT) {
+ updateWorkVariables(s);
+
+ const BodySet& bs = getModel().getBodySet();
+
+ _inertialPTrk = 0;
+ _inertialVTrk = 0;
+
+ if (get_express_body() == "ground") {
+ for (int i = 0; i < 3; ++i) {
+ _inertialPTrk[i] =
+ get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ if (getProperty_velocity_functions().size() == 0) {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ _inertialVTrk[i] = get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ } else {
+ _inertialVTrk[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+ } else {
+ _expressBody = &bs.get(get_express_body());
+
+ SimTK::Vec3 oVec, wVec;
+ // Retrieve the desired Euler angles (relative to _expressBody)
+ for (int i = 0; i < 3; ++i) {
+ oVec(i) = get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ }
+ // Construct a transform using the desired relative angles
+ SimTK::Rotation rotation;
+ rotation.setRotationToBodyFixedXYZ(oVec);
+ SimTK::Transform Tdes(rotation);
+ // Express desired rotations in ground
+ _inertialPTrk = Vector((_expressBody->getTransformInGround(s) * Tdes)
+ .R()
+ .convertRotationToBodyFixedXYZ());
+
+ for (int i = 0; i < 3; ++i) {
+ if (getProperty_velocity_functions().size() == 0) {
+ wVec[i] = get_position_functions(i).calcDerivative(
+ {0}, SimTK::Vector(1, aT));
+ } else {
+ wVec[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+ SimTK::Vec3 wVecInertial = _expressBody->expressVectorInGround(s, wVec);
+ _inertialVTrk =
+ Vector((SimTK::Pi / 180) *
+ _expressBody->getAngularVelocityInGround(s) +
+ wVecInertial);
+ }
+
+ for (int k = 0; k < 3; ++k) {
+ _pErr[k] = 0.0;
+ _vErr[k] = 0.0;
+ for (int j = 0; j < 3; ++j) {
+ _pErr[k] += (_inertialPTrk[j] * get_direction_vectors(k)[j] -
+ _p[j] * get_direction_vectors(k)[j]);
+ _vErr[k] += (_inertialVTrk[j] * get_direction_vectors(k)[j] -
+ _v[j] * get_direction_vectors(k)[j]);
+ }
+ }
+
+ // DEBUGGING
+ log_debug("t: {}", s.getTime());
+ log_debug("InertiaTask {}", this->get_wrt_body());
+ log_debug("_inertialPTrk = {}", _inertialPTrk);
+ log_debug("_inertialVTrk = {}", _inertialVTrk);
+ log_debug("_p = {}", _p);
+ log_debug("_v = {}", _v);
+ log_debug("_pErr = {}", _pErr);
+ log_debug("_vErr = {}", _vErr);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired accelerations.
+ */
+void InertiaTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aT) {
+ computeDesiredAccelerations(s, aT, aT);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired angular accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void InertiaTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) {
+ _aDes = SimTK::NaN;
+
+ // CHECK
+ checkFunctions();
+
+ // COMPUTE ERRORS
+ computeErrors(s, aTI);
+
+ // DESIRED ACCELERATION
+ double p;
+ double v;
+ double a;
+
+ for (int i = 0; i < 3; ++i) {
+ p = get_kp(i) * _pErr[i];
+ v = get_kv(i) * _vErr[i];
+ if (getProperty_acceleration_functions().size() == 0) {
+ std::vector derivComponents(2, 0);
+ // derivComponents[0]=0;
+ // derivComponents[1]=0;
+ a = get_ka(i) * get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aTF));
+ } else {
+ a = get_ka(i) *
+ get_acceleration_functions(i).calcValue(SimTK::Vector(1, aTF));
+ }
+ _aDes[i] = get_weight(i) * (a + v + p);
+
+ // PRINT
+ // printf("%s: t=%lf aDes=%lf a=%lf vErr=%lf
+ // pErr=%lf\n",getWRTBodyName().c_str(),aTF,_aDes[i],
+ // a,_vErr[i],_pErr[i]);
+ // if (i==2) std::cout << std::endl;
+ }
+}
+//_____________________________________________________________________________
+/**
+ * Compute the angular acceleration of the specified frame.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+void InertiaTask::computeAccelerations(const SimTK::State& s) {
+ // CHECK
+ if (!hasModel()) return;
+
+ // ACCELERATION
+ _a = 0;
+ const BodySet& bs = getModel().getBodySet();
+
+ _a = SimTK::Vector(
+ getModel().getMatterSubsystem().calcSystemCentralMomentum(s).get(
+ 0));
+ if (_a[0] != _a[0])
+ throw Exception(
+ "InertiaTask.computeAccelerations: ERROR- orientation task '" +
+ getName() +
+ "' references invalid acceleration components",
+ __FILE__, __LINE__);
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the Jacobian.
+ *
+ * @param s SimTK::State
+ */
+void InertiaTask::computeJacobian(const SimTK::State& s) {
+ double M = getModel().getTotalMass(s);
+ SimTK::Matrix J(3, s.getNU(), 0.0);
+ for (int i = 0; i < getModel().getBodySet().getSize(); ++i) {
+ auto m = getModel().getBodySet()[i].get_mass();
+ if (m == 0) {
+ // std::cout << "Warning: body "
+ // << getModel().getBodySet()[i].getName()
+ // << " has zero mass" << std::endl;
+ continue;
+ }
+ auto com = getModel().getBodySet()[i].get_mass_center();
+ SimTK::Matrix temp;
+ getModel().getMatterSubsystem().calcStationJacobian(s,
+ getModel().getBodySet()[i].getMobilizedBodyIndex(), com, temp);
+ J += m * temp;
+ }
+ _j = J / M;
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the Jacobian bias
+ *
+ * @param s SimTK::State
+ */
+void InertiaTask::computeBias(const SimTK::State& s) {
+ double M = getModel().getTotalMass(s);
+ SimTK::Vec3 JdotQdot(0);
+ for (int i = 0; i < getModel().getBodySet().getSize(); ++i) {
+ auto m = getModel().getBodySet()[i].get_mass();
+ if (m == 0) {
+ // std::cout << "Warning: body "
+ // << getModel().getBodySet()[i].getName()
+ // << " has zero mass" << std::endl;
+ continue;
+ }
+ auto com = getModel().getBodySet()[i].get_mass_center();
+ SimTK::Vec3 temp =
+ getModel().getMatterSubsystem().calcBiasForStationJacobian(s,
+ getModel().getBodySet()[i].getMobilizedBodyIndex(),
+ com);
+ JdotQdot += m * temp;
+ }
+ _b = Vector(-1.0 * JdotQdot / M);
+}
+
+// void InertiaTask::update(const SimTK::State& s) {
+// computeBias(s);
+// computeDesiredAccelerations(s, s.getTime());
+// computeJacobian(s);
+// }
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceInertiaTask.h b/OpenSim/Tools/TaskSpaceInertiaTask.h
new file mode 100644
index 0000000000..a301a9ca5d
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceInertiaTask.h
@@ -0,0 +1,160 @@
+#ifndef OPENSIM_TASK_SPACE_INERTIA_TASK_H_
+#define OPENSIM_TASK_SPACE_INERTIA_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceInertiaTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//============================================================================
+// INCLUDE
+//============================================================================
+#include "osimToolsDLL.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Common/PropertyDbl.h"
+#include "TaskSpaceBodyTask.h"
+
+namespace OpenSim {
+
+class Body;
+
+//=============================================================================
+//=============================================================================
+/**
+ * A class for tracking the orientation of a body.
+ */
+class OSIMTOOLS_API InertiaTask : public BodyTask {
+ OpenSim_DECLARE_CONCRETE_OBJECT(InertiaTask, BodyTask);
+
+ //=============================================================================
+ // DATA
+ //=============================================================================
+protected:
+ // Work Variables
+ const Body *_wrtBody, *_expressBody;
+
+ //=============================================================================
+ // METHODS
+ //=============================================================================
+ //--------------------------------------------------------------------------
+ // CONSTRUCTION
+ //--------------------------------------------------------------------------
+public:
+
+ /**
+ * Default constructor.
+ */
+ InertiaTask();
+
+ /**
+ * Copy constructor.
+ */
+ InertiaTask(const InertiaTask& aTask);
+
+ /**
+ * Destructor.
+ */
+ virtual ~InertiaTask();
+
+private:
+ /**
+ * Set NULL values for all member variables.
+ */
+
+ void setNull();
+ void setupProperties();
+
+ /**
+ * Update work variables
+ */
+ void updateWorkVariables(const SimTK::State& s);
+
+ //--------------------------------------------------------------------------
+ // COMPUTATIONS
+ //--------------------------------------------------------------------------
+public:
+ /**
+ * Compute the angular position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeErrors(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired accelerations.
+ */
+ void computeDesiredAccelerations(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired angular accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) override;
+
+ /**
+ * Compute the angular acceleration of the specified frame.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+ void computeAccelerations(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the Jacobian.
+ *
+ * @param s SimTK::State
+ */
+ void computeJacobian(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the Jacobian bias
+ *
+ * @param s SimTK::State
+ */
+ void computeBias(const SimTK::State& s) override;
+ // void update(const SimTK::State& s) override;
+ // void setTaskFunctions(int i, Function* aF0);
+
+//=============================================================================
+}; // END of class InertiaTask
+//=============================================================================
+//=============================================================================
+}; // namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_INERTIA_TASK_H_
diff --git a/OpenSim/Tools/TaskSpaceOrientationTask.cpp b/OpenSim/Tools/TaskSpaceOrientationTask.cpp
new file mode 100644
index 0000000000..45ecd771c8
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceOrientationTask.cpp
@@ -0,0 +1,328 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceOrientationTask.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer and Frank C. *
+ * Anderson *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//=============================================================================
+// INCLUDES
+//=============================================================================
+#include "OpenSim/Simulation/Model/Model.h"
+#include "TaskSpaceOrientationTask.h"
+
+using namespace OpenSim;
+using SimTK::Vec3;
+using SimTK::Vector;
+
+//=============================================================================
+// STATICS
+//=============================================================================
+
+//=============================================================================
+// CONSTRUCTOR(S) AND DESTRUCTOR
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Destructor.
+ */
+OrientationTask::~OrientationTask() {}
+//_____________________________________________________________________________
+/**
+ * Default constructor.
+ */
+OrientationTask::OrientationTask() {
+ setupProperties();
+ setNull();
+}
+
+//_____________________________________________________________________________
+/**
+ * Copy constructor.
+ */
+OrientationTask::OrientationTask(const OrientationTask& aTask)
+ : BodyTask(aTask) {
+ setNull();
+}
+
+//=============================================================================
+// CONSTRUCTION
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * @brief Set the Null object
+ *
+ */
+void OrientationTask::setNull() {
+ _nTrk = 3;
+ _p = SimTK::Vector(Vec3(0.0));
+ _v = SimTK::Vector(Vec3(0.0));
+ _inertialPTrk = SimTK::Vector(Vec3(0.0));
+ _inertialVTrk = SimTK::Vector(Vec3(0.0));
+ _pErrLast = Vector(Vec3(0.0));
+ _pErr = Vector(Vec3(0.0));
+ _vErrLast = Vector(Vec3(0.0));
+ _vErr = Vector(Vec3(0.0));
+ _aDes = Vector(Vec3(0.0));
+ _a = Vector(Vec3(0.0));
+}
+/**
+ * @brief Set the properties of the task
+ *
+ */
+void OrientationTask::setupProperties() {
+ // Set default direction vectors
+ set_direction_vectors(0, SimTK::Vec3(1, 0, 0));
+ set_direction_vectors(1, SimTK::Vec3(0, 1, 0));
+ set_direction_vectors(2, SimTK::Vec3(0, 0, 1));
+ setName("OrientationTask");
+ // Set default gains and weights
+ set_kp(Array(100, 3));
+ set_kv(Array(20, 3));
+ set_ka(Array(1, 3));
+ set_weight(Array(1, 3));
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief update work variables
+ *
+ * @param s current workingSimTK::State
+ */
+void OrientationTask::updateWorkVariables(const SimTK::State& s) {
+ _p = 0;
+ _v = 0;
+ if (hasModel()) {
+ const BodySet& bs = getModel().getBodySet();
+
+ if (s.getSystemStage() < SimTK::Stage::Velocity) {
+ getModel().getMultibodySystem().realize(s, SimTK::Stage::Velocity);
+ }
+
+ _wrtBody = &bs.get(get_wrt_body());
+
+ double dirCos[3][3];
+ _model->getSimbodyEngine()
+ .getDirectionCosines(s, _model->getBodySet().get(get_wrt_body()), dirCos);
+ _model->getSimbodyEngine()
+ .convertDirectionCosinesToAngles(dirCos, &_p[0], &_p[1], &_p[2]);
+ if (_p[0] != _p[0]) {
+ OPENSIM_THROW(OpenSim::Exception,"OrientationTask.updateWorkVariables: references invalid orientation components");
+ }
+
+ _v = Vector(_wrtBody->getVelocityInGround(s)[0]);
+ if (_v[0] != _v[0]) {
+ OPENSIM_THROW(OpenSim::Exception,"OrientationTask.updateWorkVariables: ERROR- orientation task reference invalid orientation velocity components");
+ }
+ }
+}
+
+//=============================================================================
+// COMPUTATIONS
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Compute the angular position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void OrientationTask::computeErrors(const SimTK::State& s, double aT) {
+ updateWorkVariables(s);
+
+ const BodySet& bs = getModel().getBodySet();
+
+ _inertialPTrk = 0;
+ _inertialVTrk = 0;
+
+ if (get_express_body() == "ground") {
+ for (int i = 0; i < 3; ++i) {
+ _inertialPTrk[i] =
+ get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ if (getProperty_velocity_functions().size() == 0) {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ _inertialVTrk[i] = get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ } else {
+ _inertialVTrk[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+ } else {
+ _expressBody = &bs.get(get_express_body());
+
+ SimTK::Vec3 oVec, wVec;
+ // Retrieve the desired Euler angles (relative to _expressBody)
+ for (int i = 0; i < 3; ++i) {
+ oVec(i) = get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ }
+ // Construct a transform using the desired relative angles
+ SimTK::Rotation rotation;
+ rotation.setRotationToBodyFixedXYZ(oVec);
+ SimTK::Transform Tdes(rotation);
+ // Express desired rotations in ground
+ _inertialPTrk = Vector((_expressBody->getTransformInGround(s) * Tdes)
+ .R()
+ .convertRotationToBodyFixedXYZ());
+
+ for (int i = 0; i < 3; ++i) {
+ if (getProperty_velocity_functions().size() == 0) {
+ wVec[i] = get_position_functions(i).calcDerivative(
+ {0}, SimTK::Vector(1, aT));
+ } else {
+ wVec[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+ SimTK::Vec3 wVecInertial = _expressBody->expressVectorInGround(s, wVec);
+ _inertialVTrk = Vector(_expressBody->getAngularVelocityInGround(s) +
+ wVecInertial); //(SimTK::Pi/180)*
+ }
+
+ for (int k = 0; k < 3; ++k) {
+ _pErr[k] = 0.0;
+ _vErr[k] = 0.0;
+ for (int j = 0; j < 3; ++j) {
+ _pErr[k] += (_inertialPTrk[j] * get_direction_vectors(k)[j] -
+ _p[j] * get_direction_vectors(k)[j]);
+ _vErr[k] += (_inertialVTrk[j] * get_direction_vectors(k)[j] -
+ _v[j] * get_direction_vectors(k)[j]);
+ }
+ }
+}
+//_____________________________________________________________________________
+
+/**
+ * @brief Compute the desired angular accelerations.
+ *
+ * @param s current working SimTK::State
+ * @param aT delta time
+ */
+void OrientationTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aT) {
+ computeDesiredAccelerations(s, aT, aT);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired angular accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void OrientationTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) {
+ _aDes = SimTK::NaN;
+
+ // CHECK
+ checkFunctions();
+
+ // COMPUTE ERRORS
+ computeErrors(s, aTI);
+
+ // DESIRED ACCELERATION
+ double p;
+ double v;
+ double a;
+
+ for (int i = 0; i < 3; ++i) {
+ p = get_kp(i) * _pErr[i];
+ v = get_kv(i) * _vErr[i];
+ if (getProperty_acceleration_functions().size() == 0) {
+ std::vector derivComponents(2, 0);
+ a = get_ka(i) * get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aTF));
+ } else {
+ a = get_ka(i) *
+ get_acceleration_functions(i).calcValue(SimTK::Vector(1, aTF));
+ }
+ _aDes[i] = get_weight(i) * (a + v + p);
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the angular acceleration of the specified frame.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+void OrientationTask::computeAccelerations(const SimTK::State& s) {
+ // CHECK
+ if (!hasModel()) return;
+
+ // ACCELERATION
+ _a = 0;
+ const BodySet& bs = getModel().getBodySet();
+
+ _wrtBody = &bs.get(get_wrt_body());
+ _a = SimTK::Vector(_wrtBody->getAngularAccelerationInGround(s));
+ if (_a[0] != _a[0])
+ OPENSIM_THROW(OpenSim::Exception,"OrientationTask.computeAccelerations: ERROR- orientation task reference invalid orientation acceleration components");
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the Jacobian for the frame given the current state
+ *
+ * @param s current working SimTK::State
+ */
+void OrientationTask::computeJacobian(const SimTK::State& s) {
+ SimTK::Matrix j_temp;
+ getModel().getMatterSubsystem().calcFrameJacobian(s,
+ getModel()
+ .getBodySet()
+ .get(get_wrt_body())
+ .getMobilizedBodyIndex(),
+ SimTK::Vec3(0), j_temp);
+ _j = j_temp(0, 0, 3, j_temp.ncol());
+}
+
+//_____________________________________________________________________________
+/**
+ * @brief Compute the bias for the task
+ *
+ * @param s current working SimTK::State
+ */
+void OrientationTask::computeBias(const SimTK::State& s) {
+ SimTK::SpatialVec jdu =
+ getModel().getMatterSubsystem().calcBiasForFrameJacobian(s,
+ getModel()
+ .getBodySet()
+ .get(get_wrt_body())
+ .getMobilizedBodyIndex(),
+ SimTK::Vec3(0));
+ _b = SimTK::Vector(-1.0 * jdu[0]);
+}
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceOrientationTask.h b/OpenSim/Tools/TaskSpaceOrientationTask.h
new file mode 100644
index 0000000000..48a49f899e
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceOrientationTask.h
@@ -0,0 +1,176 @@
+#ifndef OPENSIM_TASK_SPACE_ORIENTATION_TASK_H_
+#define OPENSIM_TASK_SPACE_ORIENTATION_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceOrientationTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer and Frank C. *
+ * Anderson *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//============================================================================
+// INCLUDE
+//============================================================================
+#include "osimToolsDLL.h"
+#include "TaskSpaceBodyTask.h"
+
+namespace OpenSim {
+
+class Body;
+
+//=============================================================================
+//=============================================================================
+/**
+ * A class for tracking the orientation of a body.
+ */
+class OSIMTOOLS_API OrientationTask : public BodyTask {
+ OpenSim_DECLARE_CONCRETE_OBJECT(OrientationTask, BodyTask);
+
+ //=============================================================================
+ // DATA
+ //=============================================================================
+protected:
+ // Work Variables
+ const Body *_wrtBody, *_expressBody;
+
+ //=============================================================================
+ // METHODS
+ //=============================================================================
+ //--------------------------------------------------------------------------
+ // CONSTRUCTION
+ //--------------------------------------------------------------------------
+public:
+ /**
+ * Default constructor.
+ */
+ OrientationTask();
+
+ /**
+ * Copy constructor.
+ */
+ OrientationTask(const OrientationTask& aTask);
+ /**
+ * Destructor.
+ */
+ virtual ~OrientationTask();
+
+private:
+ /**
+ * @brief Set the Null object
+ *
+ */
+ void setNull();
+
+ /**
+ * @brief Set the properties of the task
+ *
+ */
+ void setupProperties();
+
+ /**
+ * @brief update work variables
+ *
+ * @param s current workingSimTK::State
+ */
+ void updateWorkVariables(const SimTK::State& s);
+
+ //--------------------------------------------------------------------------
+ // COMPUTATIONS
+ //--------------------------------------------------------------------------
+public:
+ /**
+ * Compute the angular position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeErrors(const SimTK::State& s, double aT) override;
+
+ /**
+ * @brief Compute the desired angular accelerations.
+ *
+ * @param s current working SimTK::State
+ * @param aT delta time
+ */
+ void computeDesiredAccelerations(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired angular accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) override;
+
+ /**
+ * Compute the angular acceleration of the specified frame.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+ void computeAccelerations(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the Jacobian for the frame given the current state
+ *
+ * @param s current working SimTK::State
+ */
+ void computeJacobian(const SimTK::State& s) override;
+
+ /**
+ * @brief Compute the bias for the task
+ *
+ * @param s current working SimTK::State
+ */
+ void computeBias(const SimTK::State& s) override;
+
+ //void update(const SimTK::State& s) override;
+
+ /**
+ * @brief Set the model for the task
+ *
+ * @param i task function index
+ * @param aF0 task function pointer
+ */
+ //void setTaskFunctions(int i, Function* aF0);
+
+
+//=============================================================================
+}; // END of class OrientationTask
+//=============================================================================
+//=============================================================================
+}; // namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_ORIENTATION_TASK_H_
diff --git a/OpenSim/Tools/TaskSpaceStationTask.cpp b/OpenSim/Tools/TaskSpaceStationTask.cpp
new file mode 100644
index 0000000000..9a2cd73b89
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceStationTask.cpp
@@ -0,0 +1,493 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceStationTask.cpp *
+ * -------------------------------------------------------------------------- *
+* Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer and Frank C. *
+ * Anderson *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//=============================================================================
+// INCLUDES
+//=============================================================================
+#include "OpenSim/Simulation/Model/Model.h"
+#include "TaskSpaceStationTask.h"
+
+using namespace std;
+using namespace OpenSim;
+using SimTK::Vec3;
+using SimTK::Vector;
+
+//=============================================================================
+// STATICS
+//=============================================================================
+
+//=============================================================================
+// CONSTRUCTOR(S) AND DESTRUCTOR
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Destructor.
+ */
+StationTask::~StationTask() {}
+//_____________________________________________________________________________
+/**
+ * Construct a task for a specified point.
+ *
+ */
+StationTask::StationTask() : BodyTask()
+{
+ setNull();
+ constructProperties();
+}
+
+//_____________________________________________________________________________
+/**
+ * Copy constructor.
+ *
+ * @param aTask Point task to be copied.
+ */
+StationTask::StationTask(const StationTask& aTask)
+ : BodyTask(aTask) {
+ setNull();
+ copyData(aTask);
+ set_point(aTask.get_point());
+}
+
+//=============================================================================
+// CONSTRUCTION
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Set NULL values for all member variables.
+ */
+void StationTask::setNull()
+{
+ _nTrk = 3;
+ _p = SimTK::Vector(Vec3(0.0));
+ _v = SimTK::Vector(Vec3(0.0));
+ _inertialPTrk = SimTK::Vector(Vec3(0.0));
+ _inertialVTrk = SimTK::Vector(Vec3(0.0));
+ _pErrLast = Vector(Vec3(0.0));
+ _pErr = Vector(Vec3(0.0));
+ _vErrLast = Vector(Vec3(0.0));
+ _vErr = Vector(Vec3(0.0));
+ _aDes = Vector(Vec3(0.0));
+ _a = Vector(Vec3(0.0));
+}
+
+/**
+ * @brief Construct properties for the task.
+ *
+ */
+void StationTask::constructProperties()
+{
+ setName("StationTask");
+ constructProperty_point(SimTK::Vec3(0.0));
+
+ constructProperty_left_foot();
+ constructProperty_right_foot();
+}
+
+//_____________________________________________________________________________
+/**
+ * Copy only the member data of specified object.
+ */
+void StationTask::copyData(const StationTask& aTask)
+{
+ //_model = aTask.getModel();
+ copyProperty_point(aTask);
+ copyProperty_left_foot(aTask);
+ copyProperty_right_foot(aTask);
+}
+
+//_____________________________________________________________________________
+/**
+ * Update work variables
+ */
+void StationTask::updateWorkVariables(const SimTK::State& s)
+{
+ int j = 0;
+ _p = 0;
+ _v = 0;
+ if (hasModel()) {
+ const BodySet& bs = getModel().getBodySet();
+ if (s.getSystemStage() < SimTK::Stage::Velocity){
+ getModel().getMultibodySystem().realize(s, SimTK::Stage::Velocity);
+ }
+
+ if (get_wrt_body() == "center_of_mass") {
+ // COMPUTE COM OF WHOLE BODY
+ _p = Vector(getModel().calcMassCenterPosition(s));
+ _v = Vector(getModel().calcMassCenterVelocity(s));
+ if (_v[0] != _v[0]){
+ std::cout << "name " << getName() << std::endl;
+ std::cout << "time " << s.getTime() << std::endl;
+ std::cout << "v0 0 " << _v[0] << std::endl;
+ std::cout << "v0 1 " << _v[0] << std::endl;
+ std::cout << "v0 2 " << _v[0] << std::endl;
+ std::cout << "p0 0 " << _p[0] << std::endl;
+ std::cout << "p0 1 " << _p[0] << std::endl;
+ std::cout << "p0 2 " << _p[0] << std::endl;
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid velocitycomponents");
+ }
+
+ if (_p[0] != _p[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid position components");
+ }
+
+ } else {
+ _wrtBody = &bs.get(get_wrt_body());
+ SimTK::Vec3 _point = get_point();
+ _p = Vector(_wrtBody->findStationLocationInGround(s, _point));
+ if (_p[0] != _p[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.updateWorkVariables - references invalid position components");
+ }
+
+ _v = Vector(_wrtBody->findStationVelocityInGround(s, _point));
+ if (_v[0] != _v[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.updateWorkVariables - references invalid velocity components");
+ }
+ }
+ }
+}
+
+//=============================================================================
+// OPERATORS
+//=============================================================================
+//-----------------------------------------------------------------------------
+// ASSIGNMENT
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Assignment operator.
+ *
+ * @param aTask Object to be copied.
+ * @return Reference to the altered object.
+ */
+StationTask& StationTask::operator=(const StationTask& aTask)
+{
+ // BASE CLASS
+ TaskSpaceTask::operator=(aTask);
+
+ // DATA
+ copyData(aTask);
+ return (*this);
+}
+
+//=============================================================================
+// COMPUTATIONS
+//=============================================================================
+//_____________________________________________________________________________
+/**
+ * Compute the position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void StationTask::computeErrors(const SimTK::State& s, double aT)
+{
+ updateWorkVariables(s);
+
+ // COMPUTE ERRORS
+ const BodySet& bs = getModel().getBodySet();
+ _inertialPTrk = 0;
+ _inertialVTrk = 0;
+ if (get_express_body() == "ground") {
+ for (int i = 0; i < 3; ++i) {
+ _inertialPTrk[i] =
+ get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ if (getProperty_velocity_functions().size() == 0) {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ _inertialVTrk[i] = get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ } else {
+ _inertialVTrk[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+
+ } else if (get_express_body() == "base_of_support") {
+ SimTK::Vec3 pVec, vVec, origin;
+ for (int i = 0; i < 3; ++i) {
+ pVec(i) = get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ }
+ for (int i = 0; i < 3; ++i) {
+ _inertialPTrk[i] =
+ get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ if (getProperty_velocity_functions().size() == 0) {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ _inertialVTrk[i] = get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ } else {
+ _inertialVTrk[i] = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ }
+ auto& left_foot_name = get_left_foot();
+ auto& right_foot_name = get_right_foot();
+ auto& foot_r = bs.get(right_foot_name);
+ auto& foot_l = bs.get(left_foot_name);
+ SimTK::Vec3 foot_r_p = foot_r.findStationLocationInGround(
+ s, foot_r.getMassCenter());
+ SimTK::Vec3 foot_l_p = foot_l.findStationLocationInGround(
+ s, foot_l.getMassCenter());
+ auto& _point = get_point();
+ SimTK::Vec3 bosp = 0.5 * (foot_r_p + foot_l_p) + _point;
+ SimTK::Vec3 bosv =
+ getModel().getGround().findStationVelocityInGround(s, bosp);
+ for (int i = 0; i < 3; ++i) {
+ _inertialPTrk[i] += bosp[i];
+ _inertialVTrk[i] += bosv[i];
+ }
+
+ } else {
+ _expressBody = &bs.get(get_express_body());
+
+ SimTK::Vec3 pVec, vVec, origin;
+
+ for (int i = 0; i < 3; ++i) {
+ pVec(i) = get_position_functions(i).calcValue(SimTK::Vector(1, aT));
+ }
+ _inertialPTrk =
+ Vector(_expressBody->findStationLocationInGround(s, pVec));
+ if (getProperty_velocity_functions().size() == 0) {
+ // FOR REVIEW: Is this correct? Shouldn't it use the derivative of
+ // the position function?
+ _inertialVTrk =
+ Vector(_expressBody->findStationVelocityInGround(s, pVec));
+ } else {
+ for (int i = 0; i < 3; ++i) {
+ vVec(i) = get_velocity_functions(i).calcValue(
+ SimTK::Vector(1, aT));
+ }
+ // FOR REVIEW: Should origin be get_point() instead?
+ auto& _point = get_point();
+ _inertialVTrk = Vector(
+ _expressBody->findStationVelocityInGround(s, _point));
+ _inertialVTrk +=
+ Vector(vVec); // _vTrk is velocity in _expressBody, so it is
+ // simply added to velocity of _expressBody
+ // origin in inertial frame
+ }
+ }
+
+ for (int k = 0; k < 3; ++k) {
+ _pErr[k] = 0.0;
+ _vErr[k] = 0.0;
+ for (int j = 0; j < 3; ++j) {
+ _pErr[k] += (_inertialPTrk[j] * get_direction_vectors(k)[j] -
+ _p[j] * get_direction_vectors(k)[j]);
+ _vErr[k] += (_inertialVTrk[j] * get_direction_vectors(k)[j] -
+ _v[j] * get_direction_vectors(k)[j]);
+ }
+ }
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired accelerations.
+ */
+void StationTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aT) {
+ computeDesiredAccelerations(s, aT, aT);
+}
+//_____________________________________________________________________________
+/**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+void StationTask::computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) {
+ _aDes = SimTK::NaN;
+
+ checkFunctions();
+
+ computeErrors(s, aTI);
+
+ // DESIRED ACCELERATION
+ double p;
+ double v;
+ double a;
+ for (int i = 0; i < 3; ++i) {
+ p = get_kp(i) * _pErr[i];
+ v = get_kv(i) * _vErr[i];
+ if (getProperty_acceleration_functions().size() == 0) {
+ std::vector derivComponents(2);
+ derivComponents[0] = 0;
+ derivComponents[1] = 0;
+ a = get_ka(i) * get_position_functions(i).calcDerivative(
+ derivComponents, SimTK::Vector(1, aTF));
+ } else {
+ a = get_ka(i) *
+ get_acceleration_functions(i).calcValue(SimTK::Vector(1, aTF));
+ }
+ _aDes[i] = get_weight(i) * (a + v + p);
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the acceleration of the appropriate point.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * For joints (i.e., generalized coordinates), the acceleration is
+ * not computed. It has already been computed and is simply retrieved
+ * from the model.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+void StationTask::computeAccelerations(const SimTK::State& s) {
+ // CHECK
+ if (!hasModel()) return;
+
+ // ACCELERATION
+ _a = 0;
+ const BodySet& bs = getModel().getBodySet();
+ if (get_wrt_body() == "center_of_mass") {
+ SimTK::Vec3 pVec, vVec, aVec, com;
+ double Mass = 0.0;
+ for (int i = 0; i < bs.getSize(); ++i) {
+ Body& body = bs.get(i);
+ com = body.get_mass_center();
+ aVec = body.findStationAccelerationInGround(s, com);
+ if (aVec[0] != aVec[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid body acceleration components");
+ }
+
+ // ADD TO WHOLE BODY MASS
+ Mass += body.get_mass();
+ _a += SimTK::Vector(body.get_mass() * aVec);
+ }
+ _a /= Mass;
+
+ } else {
+ _wrtBody = &bs.get(get_wrt_body());
+ auto& _point = get_point();
+ _a = SimTK::Vector(
+ _wrtBody->findStationAccelerationInGround(s, _point));
+ }
+ if (_a[0] != _a[0]){
+ OPENSIM_THROW(OpenSim::Exception,
+ "StationTask.computeAccelerations - references invalid station acceleration components");
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the Jacobian for the tracked point given the current state
+ * of the model.
+ */
+void StationTask::computeJacobian(const SimTK::State& s) {
+ if (get_wrt_body() == "center_of_mass") {
+ double M = getModel().getTotalMass(s);
+ SimTK::Matrix J(3, s.getNU(), 0.0);
+ for (int i = 0; i < getModel().getBodySet().getSize(); ++i) {
+ auto m = getModel().getBodySet()[i].get_mass();
+ if (m == 0) {
+ cout << "Warning: body "
+ << getModel().getBodySet()[i].getName()
+ << " has zero mass" << endl;
+ continue;
+ }
+ auto com = getModel().getBodySet()[i].get_mass_center();
+ SimTK::Matrix temp;
+ getModel().getMatterSubsystem().calcStationJacobian(s,
+ getModel().getBodySet()[i].getMobilizedBodyIndex(), com,
+ temp);
+ J += m * temp;
+ }
+ _j = J / M;
+ } else {
+ auto& _point = get_point();
+ getModel().getMatterSubsystem().calcStationJacobian(s,
+ getModel()
+ .getBodySet()
+ .get(get_wrt_body())
+ .getMobilizedBodyIndex(),
+ _point, _j);
+ }
+}
+
+//_____________________________________________________________________________
+/**
+ * Compute the Jacobian bias term for the tracked point given the current state
+ * of the model.
+ */
+void StationTask::computeBias(const SimTK::State& s) {
+ if (get_wrt_body() == "center_of_mass") {
+ double M = getModel().getTotalMass(s);
+ SimTK::Vec3 JdotQdot(0);
+ for (int i = 0; i < getModel().getBodySet().getSize(); ++i) {
+ auto m = getModel().getBodySet()[i].get_mass();
+ if (m == 0) {
+ cout << "Warning: body "
+ << getModel().getBodySet()[i].getName()
+ << " has zero mass" << endl;
+ continue;
+ }
+ auto com = getModel().getBodySet()[i].get_mass_center();
+ SimTK::Vec3 temp =
+ getModel().getMatterSubsystem().calcBiasForStationJacobian(
+ s,
+ getModel().getBodySet()[i].getMobilizedBodyIndex(),
+ com);
+ JdotQdot += m * temp;
+ }
+ _b = Vector(-1.0 * JdotQdot / M);
+ } else {
+ auto& _point = get_point();
+ SimTK::Vec3 JdotQdot =
+ getModel().getMatterSubsystem().calcBiasForStationJacobian(s,
+ getModel()
+ .getBodySet()
+ .get(get_wrt_body())
+ .getMobilizedBodyIndex(),
+ _point);
+ _b = Vector(-1.0 * JdotQdot);
+ }
+}
+
+//=============================================================================
+// XML
+//=============================================================================
+//-----------------------------------------------------------------------------
+// UPDATE FROM XML NODE
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Update this object based on its XML node.
+ *
+ * @param aDeep If true, update this object and all its child objects
+ * (that is, member variables that are Object's); if false, update only
+ * the member variables that are not Object's.
+ */
+void StationTask::updateFromXMLNode(
+ SimTK::Xml::Element& aNode, int versionNumber) {
+ Super::updateFromXMLNode(aNode, versionNumber);
+}
diff --git a/OpenSim/Tools/TaskSpaceStationTask.h b/OpenSim/Tools/TaskSpaceStationTask.h
new file mode 100644
index 0000000000..e375ce3c56
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceStationTask.h
@@ -0,0 +1,210 @@
+#ifndef OPENSIM_TASK_SPACE_STATION_TASK_H_
+#define OPENSIM_TASK_SPACE_STATION_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceStationTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer and Frank C. *
+ * Anderson *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+//============================================================================
+// INCLUDE
+//============================================================================
+#include "osimToolsDLL.h"
+#include "OpenSim/Simulation/osimSimulation.h"
+#include "OpenSim/Common/PropertyDbl.h"
+#include "TaskSpaceBodyTask.h"
+
+namespace OpenSim {
+
+class Body;
+
+//=============================================================================
+//=============================================================================
+/**
+ * A class for specifying and computing parameters for tracking a point.
+ *
+ * @author Frank C. Anderson
+ * @version 1.0
+ */
+class OSIMTOOLS_API StationTask : public BodyTask {
+ OpenSim_DECLARE_CONCRETE_OBJECT(StationTask, BodyTask);
+
+public:
+ OpenSim_DECLARE_PROPERTY(point, SimTK::Vec3,
+ "Point in body frame with respect to which an objective is tracked.");
+
+ OpenSim_DECLARE_OPTIONAL_PROPERTY(left_foot, std::string,
+ "Name of body representing left foot. Used to calculate base of support.");
+
+ OpenSim_DECLARE_OPTIONAL_PROPERTY(right_foot, std::string,
+ "Name of body representing right foot. Used to calculate base of support.");
+
+ //=============================================================================
+ // DATA
+ //=============================================================================
+protected:
+ // REFERENCES
+ const Body *_wrtBody, *_expressBody;
+
+ //=============================================================================
+ // METHODS
+ //=============================================================================
+public:
+ //--------------------------------------------------------------------------
+ // CONSTRUCTION
+ //--------------------------------------------------------------------------
+ /**
+ * Construct a task for a specified point.
+ *
+ */
+ StationTask();
+
+ /**
+ * Copy constructor.
+ *
+ * @param aTask Point task to be copied.
+ */
+ StationTask(const StationTask& aTask);
+
+ /**
+ * Destructor.
+ */
+ virtual ~StationTask();
+
+private:
+ /**
+ * Set NULL values for all member variables.
+ */
+ void setNull();
+
+ /**
+ * @brief Construct properties for the task.
+ *
+ */
+ void constructProperties();
+
+ /**
+ * Copy only the member data of specified object.
+ */
+ void copyData(const StationTask& aTask);
+
+ /**
+ * Update work variables
+ */
+ void updateWorkVariables(const SimTK::State& s);
+
+ //--------------------------------------------------------------------------
+ // OPERATORS
+ //--------------------------------------------------------------------------
+public:
+#ifndef SWIG
+ /**
+ * Assignment operator.
+ *
+ * @param aTask Object to be copied.
+ * @return Reference to the altered object.
+ */
+ StationTask& operator=(const StationTask& aTask);
+#endif
+
+ //--------------------------------------------------------------------------
+ // COMPUTATIONS
+ //--------------------------------------------------------------------------
+ /**
+ * Compute the position and velocity errors.
+ * This method assumes the states have been set for the model.
+ *
+ * @param aT Current time in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeErrors(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired accelerations.
+ */
+ void computeDesiredAccelerations(const SimTK::State& s, double aT) override;
+
+ /**
+ * Compute the desired accelerations.
+ * This method assumes that the states have been set for the model.
+ *
+ * @param aTI Initial time of the controlled interval in real time units.
+ * @param aTF Final time of the controlled interval in real time units.
+ * @see Model::set()
+ * @see Model::setStates()
+ */
+ void computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) override;
+
+ /**
+ * Compute the acceleration of the appropriate point.
+ * For the computed accelerations to be correct,
+ * Model::computeAccelerations() must have already been called.
+ *
+ * For joints (i.e., generalized coordinates), the acceleration is
+ * not computed. It has already been computed and is simply retrieved
+ * from the model.
+ *
+ * @see Model::computeAccelerations()
+ * @see suTrackObject::getAcceleration()
+ */
+ void computeAccelerations(const SimTK::State& s) override;
+
+ /**
+ * Compute the Jacobian for the tracked point given the current state
+ * of the model.
+ */
+ void computeJacobian(const SimTK::State& s) override;
+
+ /**
+ * Compute the Jacobian bias term for the tracked point given the current state
+ * of the model.
+ */
+ void computeBias(const SimTK::State& s) override;
+ //--------------------------------------------------------------------------
+ // XML
+ //--------------------------------------------------------------------------
+ /**
+ * Update this object based on its XML node.
+ *
+ * @param aDeep If true, update this object and all its child objects
+ * (that is, member variables that are Object's); if false, update only
+ * the member variables that are not Object's.
+ */
+ void updateFromXMLNode(
+ SimTK::Xml::Element& aNode, int versionNumber = -1) override;
+
+//=============================================================================
+}; // END of class StationTask
+//=============================================================================
+//=============================================================================
+}; // namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_STATION_TASK_H_
diff --git a/OpenSim/Tools/TaskSpaceTask.cpp b/OpenSim/Tools/TaskSpaceTask.cpp
new file mode 100644
index 0000000000..b01f0db8f7
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceTask.cpp
@@ -0,0 +1,369 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim TaskSpace: TaskSpaceTask.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer and Frank C. *
+ * Anderson *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "TaskSpaceTask.h"
+
+#include "OpenSim/Common/Constant.h"
+#include "OpenSim/Simulation/Model/Model.h"
+
+using namespace OpenSim;
+using namespace SimTK;
+using namespace std;
+
+TaskSpaceTask::TaskSpaceTask(){
+ constructProperties();
+ setNull();
+}
+
+void TaskSpaceTask::constructProperties() {
+ constructProperty_priority(0);
+ constructProperty_position_functions();
+ constructProperty_velocity_functions();
+ constructProperty_acceleration_functions();
+ constructProperty_kp();
+ constructProperty_kv();
+ constructProperty_ka();
+ constructProperty_weight();
+}
+
+void TaskSpaceTask::copyData(const TaskSpaceTask& aTask) {
+ copyProperty_priority(aTask);
+ copyProperty_position_functions(aTask);
+ copyProperty_velocity_functions(aTask);
+ copyProperty_acceleration_functions(aTask);
+ copyProperty_kp(aTask);
+ copyProperty_kv(aTask);
+ copyProperty_ka(aTask);
+ copyProperty_weight(aTask);
+}
+
+TaskSpaceTask& TaskSpaceTask::operator=(const TaskSpaceTask& aTask) {
+ // BASE CLASS
+ Object::operator=(aTask);
+
+ // DATA
+ copyData(aTask);
+
+ return (*this);
+}
+
+void TaskSpaceTask::setNull() {
+ setName(DEFAULT_NAME);
+
+ _nTrk = 0;
+ _pErrLast = SimTK::Vector(Vec3(0.0));
+ _pErr = SimTK::Vector(Vec3(0.0));
+ _vErrLast = SimTK::Vector(Vec3(0.0));
+ _vErr = SimTK::Vector(Vec3(0.0));
+ _aDes = SimTK::Vector(Vec3(0.0));
+ _p = SimTK::Vector(Vec3(0.0));
+ _v = SimTK::Vector(Vec3(0.0));
+ _inertialPTrk = SimTK::Vector(Vec3(0.0));
+ _inertialVTrk = SimTK::Vector(Vec3(0.0));
+ _a = SimTK::Vector(Vec3(0.0));
+ _j = SimTK::Vector(Vec3(0.0));
+}
+
+void TaskSpaceTask::extendFinalizeFromProperties()
+{
+ Super::extendFinalizeFromProperties();
+}
+
+void TaskSpaceTask::extendConnectToModel(Model& aModel)
+{
+ Super::extendConnectToModel(aModel);
+}
+
+//-----------------------------------------------------------------------------
+// VALIDATION
+//-----------------------------------------------------------------------------
+void TaskSpaceTask::checkFunctions() const
+{
+ if (getProperty_position_functions().size() == 0) {
+ log_warn("TaskSpaceTask position tracking function not set.");
+ return;
+ }
+}
+
+//-----------------------------------------------------------------------------
+// TASK KINEMATICS
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Get the task position.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task position.
+ * @throws Exception for an invalid task.
+ */
+double TaskSpaceTask::getTaskPosition(int aWhich, double aT) const {
+ if ((aWhich < 0) || (aWhich >= _nTrk)) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "TaskSpaceTask:Invalid Task");
+ }
+ double position =
+ get_position_functions(aWhich).calcValue(SimTK::Vector(1, aT));
+ return (position);
+}
+//_____________________________________________________________________________
+/**
+ * Get the task velocity.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task velocity.
+ * @throws Exception for an invalid task.
+ */
+double TaskSpaceTask::getTaskVelocity(int aWhich, double aT) const {
+ if ((aWhich < 0) || (aWhich >= _nTrk)) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "TaskSpaceTask:Invalid Task");
+ }
+
+ double velocity;
+ if (getProperty_velocity_functions().size() > aWhich) {
+ velocity =
+ get_velocity_functions(aWhich).calcValue(SimTK::Vector(1, aT));
+ } else {
+ std::vector derivComponents(1);
+ derivComponents[0] = 0;
+ velocity = get_position_functions(aWhich).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ }
+
+ return (velocity);
+} //_____________________________________________________________________________
+/**
+ * Get the task acceleration.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task acceleration.
+ * @throws Exception for an invalid task.
+ */
+double TaskSpaceTask::getTaskAcceleration(int aWhich, double aT) const {
+ if ((aWhich < 0) || (aWhich >= _nTrk)) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "TaskSpaceTask:Invalid Task");
+ }
+
+ double acceleration;
+ if (getProperty_acceleration_functions().size() > aWhich) {
+ acceleration = get_acceleration_functions(aWhich).calcValue(
+ SimTK::Vector(1, aT));
+ } else {
+ std::vector derivComponents(2);
+ derivComponents[0] = 0;
+ derivComponents[1] = 0;
+ acceleration = get_position_functions(aWhich).calcDerivative(
+ derivComponents, SimTK::Vector(1, aT));
+ }
+ return (acceleration);
+}
+
+//-----------------------------------------------------------------------------
+// LAST POSITION ERRORS
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Set the last achieved position error. This information is useful for
+ * checking that error dynamics are being followed.
+ *
+ * @param aE0 Last position error for track goal 0.
+ * @param aE1 Last position error for track goal 1.
+ * @param aE2 Last position error for track goal 2.
+ */
+void TaskSpaceTask::setPositionErrorLast(double aE0, double aE1, double aE2) {
+ _pErrLast[0] = aE0;
+ _pErrLast[1] = aE1;
+ _pErrLast[2] = aE2;
+}
+//_____________________________________________________________________________
+/**
+ * Get the last achieved position error for the track goal at a given index.
+ * This information is useful for checking that error dynamics are being
+ * followed.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Last position error.
+ */
+double TaskSpaceTask::getPositionErrorLast(int aWhich) const {
+ if (aWhich < 0) return (0.0);
+ if (aWhich >= _nTrk) return (0.0);
+ return (_pErrLast[aWhich]);
+}
+
+//-----------------------------------------------------------------------------
+// LAST VELOCITY ERRORS
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Set the last achieved velocity error. This information is useful for
+ * checking that error dynamics are being followed.
+ *
+ * @param aE0 Last velocity error for track goal 0.
+ * @param aE1 Last velocity error for track goal 1.
+ * @param aE2 Last velocity error for track goal 2.
+ */
+void TaskSpaceTask::setVelocityErrorLast(double aE0, double aE1, double aE2) {
+ _vErrLast[0] = aE0;
+ _vErrLast[1] = aE1;
+ _vErrLast[2] = aE2;
+}
+//_____________________________________________________________________________
+/**
+ * Get the last achieved velocity error. This information is useful for
+ * checking that error dynamics are being followed.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Last velocity error.
+ */
+double TaskSpaceTask::getVelocityErrorLast(int aWhich) const {
+ if (aWhich < 0) return (0.0);
+ if (aWhich >= _nTrk) return (0.0);
+ return (_vErrLast[aWhich]);
+}
+
+//-----------------------------------------------------------------------------
+// TRACK ERRORS
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Get the position track error of a specified track goal.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Error
+ */
+double TaskSpaceTask::getPositionError(int aWhich) const {
+ if (aWhich < 0) return (0.0);
+ if (aWhich >= _nTrk) return (0.0);
+ return (_pErr[aWhich]);
+}
+//_____________________________________________________________________________
+/**
+ * Get the velocity track error of a specified track goal.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Error
+ */
+double TaskSpaceTask::getVelocityError(int aWhich) const {
+ if (aWhich < 0) return (0.0);
+ if (aWhich >= _nTrk) return (0.0);
+ return (_vErr[aWhich]);
+}
+
+//-----------------------------------------------------------------------------
+// DESIRED ACCELERATION
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Get the desired acceleration of a specified track goal.
+ * The method computeDesiredAccelerations() must be called first for the
+ * values returned by this method to be valid.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Desired acceleration. SimTK::NaN is returned on an error.
+ */
+double TaskSpaceTask::getDesiredAcceleration(int aWhich) const {
+ if (aWhich < 0) return (SimTK::NaN);
+ if (aWhich >= _nTrk) return (SimTK::NaN);
+ return (_aDes[aWhich]);
+}
+
+SimTK::Vector TaskSpaceTask::getDesiredAccelerations() const { return (_aDes); }
+//-----------------------------------------------------------------------------
+// ACCELERATION
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Get the acceleration of a specified track goal. The acceleration returned
+ * is the dot product of the appropriate track-goal direction and the
+ * acceleration of the point or orientation in question. In the case of
+ * generalized coordinates, the acceleration of the generalized coordinate
+ * is returned (i.e., a direction is not appropriate).
+ *
+ * For the value returned by this method to be valid, the method
+ * computeAccelerations() must be called first.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Acceleration. SimTK::NaN is returned on an error.
+ */
+double TaskSpaceTask::getAcceleration(int aWhich) const {
+ if (aWhich < 0) return (SimTK::NaN);
+ if (aWhich >= _nTrk) return (SimTK::NaN);
+ return (_a[aWhich]);
+}
+
+//-----------------------------------------------------------------------------
+// JACOBIAN
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Get a copy of the Jacobian matrix.
+ *
+ * For the value returned by this method to be valid, the method
+ * computeJacobian() must be called first.
+ *
+ * @return Jacobian. SimTK::NaN is returned on an error.
+ */
+SimTK::Matrix TaskSpaceTask::getJacobian() const
+{
+ return _j;
+}
+
+//_____________________________________________________________________________
+/**
+ * Get a copy of the Jacobian bias vector.
+ *
+ * For the value returned by this method to be valid, the method
+ * computeBias() must be called first.
+ *
+ * @return Bias. SimTK::NaN is returned on an error.
+ */
+SimTK::Vector TaskSpaceTask::getBias() const
+{
+ return _b;
+}
+
+//=============================================================================
+// COMPUTATIONS
+//=============================================================================
+void TaskSpaceTask::update(const SimTK::State& s) {
+ computeBias(s);
+ computeDesiredAccelerations(s, s.getTime());
+ computeJacobian(s);
+
+ log_debug("{} desired accelerations: {}", getName(), _aDes);
+ log_debug("{} position error: {}", getName(), _pErr);
+ log_debug("{} velocity error: {}", getName(), _vErr);
+}
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceTask.h b/OpenSim/Tools/TaskSpaceTask.h
new file mode 100644
index 0000000000..6aa6b19b2a
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceTask.h
@@ -0,0 +1,214 @@
+#ifndef OPENSIM_TASK_SPACE_TASK_H_
+#define OPENSIM_TASK_SPACE_TASK_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceTask.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "osimToolsDLL.h"
+
+#include "OpenSim/Simulation/Model/ModelComponent.h"
+#include "OpenSim/Common/Function.h"
+
+namespace OpenSim {
+
+/**
+ * \brief TaskSpace analog for CMC_Task or TrackingTask
+ */
+class OSIMTOOLS_API TaskSpaceTask : public ModelComponent {
+ OpenSim_DECLARE_ABSTRACT_OBJECT(TaskSpaceTask, ModelComponent);
+
+public:
+ //=============================================================================
+ // PROPERTIES
+ //=============================================================================
+ // PROPERTIES
+ OpenSim_DECLARE_PROPERTY(
+ priority, int, "Priority level of the task. 0 is highest.");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(position_functions, OpenSim::Function,
+ 3, "Position task functions. Different types of tasks can "
+ "require different numbers of task functions. For example, to track"
+ "a joint angle, only one task function is needed. However, to track"
+ "a position, up to three task functions may be needed. If tracking "
+ "experimental data, do not specify these functions - splines will be "
+ "generated from the data.");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(velocity_functions, OpenSim::Function,
+ 3, "Velocity task functions. If velocity task functions are not "
+ "specified, derivatives of the position task function are used. If "
+ "tracking experimental data, do not specify these functions - splines "
+ "will be generated from the data.");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(acceleration_functions,
+ OpenSim::Function, 3,
+ "Velocity task functions. If acceleration task functions are not "
+ "specified, derivatives of the position task function are used. If "
+ "tracking experimental data, do not specify these functions - splines "
+ "will be generated from the data.");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(weight, double, 3, "Weight with which a "
+ "task is tracked relative to other tasks. To track a task more "
+ "tightly, make the weight larger.");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(kp, double, 3,
+ "Position error feedback gain (stiffness). "
+ "To achieve critical damping of errors, choose kv = 2*sqrt(kp).");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(kv, double, 3,
+ "Velocity error feedback gain (damping). "
+ "To achieve critical damping of errors, choose kv = 2*sqrt(kp).");
+
+ OpenSim_DECLARE_LIST_PROPERTY_ATMOST(ka, double, 3,
+ "Feedforward acceleration gain. "
+ "This is normally set to 1.0, so no gain.");
+
+ //=============================================================================
+ // PUBLIC METHODS
+ //=============================================================================
+
+ TaskSpaceTask();
+ virtual ~TaskSpaceTask() {}
+#ifndef SWIG
+ TaskSpaceTask& operator=(const TaskSpaceTask& aTaskObject);
+#endif
+ virtual void update(const SimTK::State& s);
+ virtual void computeErrors(const SimTK::State& s, double aT) = 0;
+ virtual void computeDesiredAccelerations(
+ const SimTK::State& s, double aT) = 0;
+ virtual void computeDesiredAccelerations(
+ const SimTK::State& s, double aTI, double aTF) = 0;
+ virtual void computeAccelerations(const SimTK::State& s) = 0;
+ virtual void computeJacobian(const SimTK::State& s) = 0;
+ virtual void computeBias(const SimTK::State& s) = 0;
+
+ /**
+ * Get the task position.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task position.
+ * @throws Exception for an invalid task.
+ */
+ double getTaskPosition(int aWhich, double aT) const;
+
+ /**
+ * Get the task velocity.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task velocity.
+ * @throws Exception for an invalid task.
+ */
+ double getTaskVelocity(int aWhich, double aT) const;
+
+ /**
+ * Get the task acceleration.
+ *
+ * @param aWhich Specifies which task goal (0, 1, or 2).
+ * @param aT Time (in real time units).
+ * @return Task acceleration.
+ * @throws Exception for an invalid task.
+ */
+ double getTaskAcceleration(int aWhich, double aT) const;
+
+ /**
+ * Set the last achieved position error. This information is useful for
+ * checking that error dynamics are being followed.
+ *
+ * @param aE0 Last position error for track goal 0.
+ * @param aE1 Last position error for track goal 1.
+ * @param aE2 Last position error for track goal 2.
+ */
+ void setPositionErrorLast(double aE0, double aE1 = 0.0, double aE2 = 0.0);
+
+ /**
+ * Get the last achieved position error for the track goal at a given index.
+ * This information is useful for checking that error dynamics are being
+ * followed.
+ *
+ * @param aWhich Specifies which track goal (0, 1, or 2).
+ * @return Last position error.
+ */
+ double getPositionErrorLast(int aWhich) const;
+ void setVelocityErrorLast(double aE0, double aE1 = 0.0, double aE2 = 0.0);
+ double getVelocityErrorLast(int aWhich) const;
+ // ERRORS
+ double getPositionError(int aWhich) const;
+ double getVelocityError(int aWhich) const;
+ // DESIRED ACCELERATIONS
+ double getDesiredAcceleration(int aWhich) const;
+ SimTK::Vector getDesiredAccelerations() const;
+ // ACCELERATIONS
+ double getAcceleration(int aWhich) const;
+ // JACOBIAN
+ SimTK::Matrix getJacobian() const;
+ SimTK::Vector getBias() const;
+
+protected:
+ // Model component interface.
+ void extendFinalizeFromProperties() override;
+ void extendConnectToModel(Model& model) override;
+
+ // const Model* _model;
+ int _nTrk;
+ void checkFunctions() const;
+
+ /** Last position error. */
+ SimTK::Vector _pErrLast;
+ /** Position error. */
+ SimTK::Vector _pErr;
+ /** Last velocity error. */
+ SimTK::Vector _vErrLast;
+ /** Velocity error. */
+ SimTK::Vector _vErr;
+ /** Desired accelerations. */
+ SimTK::Vector _aDes;
+ /** Positions. */
+ SimTK::Vector _p, _inertialPTrk;
+ /** Velocities. */
+ SimTK::Vector _v, _inertialVTrk;
+ /** Accelerations. */
+ SimTK::Vector _a;
+ /** Jacobian. */
+ SimTK::Matrix _j;
+ /** Jacobian bias. */
+ SimTK::Vector _b;
+
+private:
+ void constructProperties();
+ void setNull();
+ void copyData(const TaskSpaceTask& aTaskObject);
+
+//=============================================================================
+}; // end of class TaskSpaceTask
+//=============================================================================
+} // end of namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_TASK_H_
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceTaskSet.h b/OpenSim/Tools/TaskSpaceTaskSet.h
new file mode 100644
index 0000000000..7e3cc7e991
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceTaskSet.h
@@ -0,0 +1,59 @@
+#ifndef OPENSIM_TASK_SPACE_TASK_SET_H_
+#define OPENSIM_TASK_SPACE_TASK_SET_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceTaskSet.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "OpenSim/Simulation/Model/ModelComponentSet.h"
+#include "TaskSpaceTask.h"
+
+namespace OpenSim {
+//=============================================================================
+//=============================================================================
+/**
+ * A class for holding a set of tasks.
+ */
+class OSIMTOOLS_API TaskSpaceTaskSet : public ModelComponentSet {
+OpenSim_DECLARE_CONCRETE_OBJECT(TaskSpaceTaskSet, ModelComponentSet);
+
+public:
+ /** Use Super's constructors. @see ModelComponentSet */
+ using Super::Super;
+
+ // default copy, assignment operator, and destructor
+
+//=============================================================================
+}; // END of class TaskSpaceTaskSet
+//=============================================================================
+//=============================================================================
+
+} // end of namespace OpenSim
+
+#endif // OPENSIM_TASK_SPACE_TASK_SET_H_
diff --git a/OpenSim/Tools/TaskSpaceTorqueController.cpp b/OpenSim/Tools/TaskSpaceTorqueController.cpp
new file mode 100644
index 0000000000..28dd4a1712
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceTorqueController.cpp
@@ -0,0 +1,501 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim TaskSpace: TaskSpaceTorqueController.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * and Dimitar Stanev *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include
+
+#include "OpenSim/Actuators/CoordinateActuator.h"
+
+#include "TaskSpaceComputeControlsEventHandler.h"
+#include "TaskSpaceUtilities.h"
+#include "TaskSpaceTorqueController.h"
+
+using namespace OpenSim;
+using namespace SimTK;
+using namespace std;
+
+TaskSpaceTorqueController::TaskSpaceTorqueController()
+{
+ constructProperties();
+ setNull();
+}
+
+TaskSpaceTorqueController::TaskSpaceTorqueController(const TaskSpaceTorqueController& aController)
+ : Super(aController)
+{
+ copyData(aController);
+}
+
+void TaskSpaceTorqueController::constructProperties()
+{
+ constructProperty_ConstraintModel(NoConstraintModel());
+ constructProperty_excluded_coords();
+ constructProperty_control_strategy("default");
+ constructProperty_use_constraint_nullspace(true);
+
+ TaskSpaceTaskSet tasks;
+ tasks.setName(IO::Lowercase(tasks.getConcreteClassName()));
+ constructProperty_TaskSpaceTaskSet(tasks);
+}
+
+void TaskSpaceTorqueController::setNull()
+{
+ _dt = 0.001;
+ _lastDT = 0.0;
+ _restoreDT = false;
+ _tf = 0;
+ _targetDT = 1.0e-2;
+ _checkTargetTime = true;
+}
+
+void TaskSpaceTorqueController::copyData(const TaskSpaceTorqueController& aController)
+{
+ copyProperty_ConstraintModel(aController);
+ copyProperty_excluded_coords(aController);
+ copyProperty_TaskSpaceTaskSet(aController);
+ copyProperty_control_strategy(aController);
+ copyProperty_use_constraint_nullspace(aController);
+
+ _dt = aController._dt;
+ _tf = aController._tf;
+ _lastDT = aController._lastDT;
+ _restoreDT = aController._restoreDT;
+ _checkTargetTime = aController._checkTargetTime;
+}
+
+void TaskSpaceTorqueController::extendFinalizeFromProperties()
+{
+ Super::extendFinalizeFromProperties();
+
+ //validate priority levels
+ std::set priority_levels;
+ for (int i = 0; i < get_TaskSpaceTaskSet().getSize(); ++i) {
+ auto& task = get_TaskSpaceTaskSet().get(i);
+ priority_levels.insert(task.get_priority());
+ }
+ int i=0;
+ for (auto p : priority_levels) {
+ if (p!=i) {
+ throw runtime_error(
+ "Task priority levels must be consecutive starting at zero.");
+ }
+ i += 1;
+ max_priority = i;
+ }
+ log_debug("priority_levels: {}", max_priority);
+}
+
+Matrix TaskSpaceTorqueController::createSelectionMatrix() const {
+ Matrix B;
+ if (hasModel()) {
+ int ncoords = getModel().getNumCoordinates();
+ B.resize(ncoords, ncoords);
+ // All coordinates are actuated by default
+ B = 1;
+ auto state = _model->getWorkingState();
+ auto& matter = _model->getMatterSubsystem();
+ const Property& excluded_coords = getProperty_excluded_coords();
+
+ const auto& cs = _model->getCoordinateSet();
+
+ for (int c = 0; c < excluded_coords.size(); ++c) {
+ auto& coord = cs.get(get_excluded_coords(c));
+ int mbti = matter.getMobilizedBody(coord.getBodyIndex())
+ .getFirstUIndex(state) +
+ coord.getMobilizerQIndex();
+ B.updDiag()[mbti] = 0.0;
+ }
+ }
+ return B;
+}
+
+void TaskSpaceTorqueController::printResults(const string &aPrefix, const string &aDir) {
+ appliedForces.print(aDir + "/" + aPrefix + "_TaskSpaceTorqueController.sto");
+}
+
+// Controller Interface.
+// compute the control value for all actuators this Controller is responsible for
+void TaskSpaceTorqueController::computeControls(const SimTK::State& s, SimTK::Vector& controls) const
+{
+ // Make sure to use the order consistent with Simbody's representation
+ const auto& cs = getModel().getCoordinatesInMultibodyTreeOrder();
+ log_debug("integrator time: {}", s.getTime());
+ auto tau = calcTau(s);
+ for (int i = 0; i < cs.size(); ++i) {
+ string name = cs[i]->getName() + "_control";
+
+ getActuatorSet().get(name).addInControls(Vector(1, tau[i]), controls);
+ }
+}
+
+SimTK::Vector TaskSpaceTorqueController::calcTau(const SimTK::State& s) const
+{
+ //Start a clock
+ using namespace std::chrono;
+ auto start = high_resolution_clock::now();
+
+ Matrix B = createSelectionMatrix();
+
+ //Allocate variable for torque data for the n coordinate actuators
+ auto tau = Vector(n, 0.0); //total task torque
+ Matrix taua(n, 1, 0.0); //aggregate torque during iterative calculations
+
+ //Evaluate the constraint data
+ auto constraint_data = get_ConstraintModel().calcConstraintData(getModel(), s);
+ //Constraint Jacobian
+ Matrix Jc = constraint_data.Jc;
+ //Transpose of the constraint null space matrix
+ Matrix NcT = constraint_data.NcT;
+ //Constraint bias
+ Matrix bc = constraint_data.bc;
+ //Mass matrix M
+ Matrix M = constraint_data.M;
+ //Constraint consistent inverse of the mass matrix
+ Matrix McInv = constraint_data.McInv;
+ //External (contact) forces
+ Matrix Fext = constraint_data.Fext;
+ //Total applied forces (gravity, coriolis, passive muscle/tendon, etc)
+ Vector Fapplied = calcTotalGeneralizedForces(s, getModel());
+
+ //--------------------------------------------------------------------------
+ // Construct augmented Jacobian matrices and desired acceleration vectors,
+ // sorted by priority level.
+ //--------------------------------------------------------------------------
+ Matrix Ja; // aggregate Jacobian for all tasks
+
+ /* Priority-sorted augmented Jacobian matrix. */
+ std::vector Jt_p;
+
+ // Priority-sorted desired accelerations
+ std::vector xtddot_p;
+
+ // Priority-sorted task bias
+ std::vector bt_p;
+
+ Jt_p.resize(max_priority+1);
+ xtddot_p.resize(max_priority+1);
+ bt_p.resize(max_priority+1);
+
+ //Pre-assemble the stacked Jacobian, desired acceleration, and task bias
+ //matrices for use in future calculations.
+ for (int i = 0; i < get_TaskSpaceTaskSet().getSize(); ++i) {
+ auto& task = get_TaskSpaceTaskSet().get(i);
+ const int& priority = task.get_priority();
+ task.update(s);
+ xtddot_p[priority] = concatenate(
+ xtddot_p[priority],
+ task.getDesiredAccelerations(),
+ 0)
+ .getAsVector();
+ Jt_p[priority] = concatenate(Jt_p[priority], task.getJacobian(), 0);
+ bt_p[priority] =
+ concatenate(bt_p[priority], task.getBias(), 0).getAsVector();
+ }
+
+ //Aggregate task null space
+ Matrix N_ai(NcT.nrow(), NcT.ncol(), 0.0);
+ if (get_use_constraint_nullspace()) {
+ //By default, constraints get priority -1. However, this may conflict
+ //with movement controllers that utilize the SupportModel, as ground
+ //contact is treated as a constraint.
+ N_ai = NcT;
+ }
+ else {
+ N_ai = 1.0;
+ }
+
+ //If no external forces, set contributions to zero
+ if (Fext.nelt() == 0) {
+ Fext = Vector(Jc.nrow(), 0.0);
+ }
+
+ //Iterate over priority levels and calculate task torques for each set of
+ //tasks
+ for (int i = 0; i < max_priority; ++i) {
+ //Append task Jacobians for current priority level to existing augmented
+ //Jacobian matrix Ja
+ Ja = concatenate(Ja, Jt_p[i], 0);
+
+ //Task Jacobian at priority level i
+ Matrix J_ai = Jt_p[i];
+ //Dynamically consistent effective mass matrix
+ Matrix Lambda_ai = DampedSVDPseudoinverse(J_ai * McInv * N_ai * ~J_ai);
+
+ //Task space force contribution terms
+ Matrix tf_xtddot = Lambda_ai * xtddot_p[i]; //task accelerations
+ Matrix tf_gc = Lambda_ai * J_ai * McInv * NcT * Fapplied; //gravity and coriolis
+ Matrix tf_bt = Lambda_ai * bt_p[i]; //task bias
+ Matrix tf_bc = Lambda_ai * J_ai * McInv * bc; //constraint bias
+
+ // compute total task space force
+ auto F = tf_xtddot + tf_gc + tf_bt + tf_bc;
+
+ //Project task forces into null space of higher priority tasks
+ taua += N_ai * ~J_ai * F;
+
+ //Update the aggregate
+ N_ai = N_ai * (1 - ~J_ai * Lambda_ai * J_ai * McInv * N_ai);
+ }
+
+ //Filter aggregate task torques through constraint null space to make
+ //dynamically consistent, and account for floating base (underactuation)
+ if (Ja.nelt() > 0) {
+ Matrix Lambda_a_bar = DampedSVDPseudoinverse(Ja * McInv * NcT * ~Ja);
+ Matrix Ja_bar = Lambda_a_bar * Ja * McInv * NcT;
+
+ //Constraint consistent aggregate null space projection
+ Matrix Na_bar = 1.0 - (~Ja * Ja_bar);
+
+ //Account for "virtual dofs" in a floating base model.
+ Matrix Beta;
+ if ((1.0-B).norm() <= 1e-8) {
+ //B == identity
+ Beta = B;
+ } else {
+ Beta = 1.0 - (Na_bar * DampedSVDPseudoinverse((1.0 - B) * Na_bar) * (1.0 - B));
+ }
+
+ //Apply the filter to the computed task torques. The selection matrix B is included
+ //to ensure the constraint tau=B*tau is not violated. In general, Beta*taua will result
+ //in zero forces/torques at excluded coordinates. However, in certain infeasible scenarios
+ //the constraint will be violated and nonzero forces/torques may be computed for excluded
+ //coordinates. Explicitly enforcing tau=B*tau means that the simulation will fail rather
+ //than succeeding with fictitious forces/torques applied.
+ tau = (B * Beta * taua).getAsVector();
+ } else {
+ tau = Vector(n, 0.0);
+ }
+
+ //FOR REVIEW: Dimitar Stanev's original code utilized these additional
+ // calculations for the control torques. There may be a better
+ // way to incorporate them. Also need to check whether N_ai or
+ // Na_bar should be used.
+ if (get_control_strategy() == "default") {
+ //Just use tau
+ } else if (get_control_strategy() == "force") {
+ tau = tau + N_ai*(Fapplied + constraint_data.bc);
+ } else if (get_control_strategy() == "velocity") {
+ tau = tau - 20*N_ai*s.getU();
+ } else {
+ log_error("Control strategy not recognized.");
+ }
+
+ //Print timing info
+ auto stop = high_resolution_clock::now();
+ auto duration = duration_cast(stop - start);
+ log_debug("calcTaskDynamics: {}s (last time step {}ms)", s.getTime(), duration.count());
+
+ //Print calculated task torques
+ log_debug("tau= {}", tau);
+
+ return tau;
+}
+
+void TaskSpaceTorqueController::extendConnectToModel(Model& model) {
+ Super::extendConnectToModel(model);
+ // construct labels for the applied forces
+ Array storageLabels;
+ storageLabels.append("time");
+
+ // create an actuator for each generalized coordinate in the model
+ // add these actuators to the model and set their indexes
+ auto& cs = model.getCoordinateSet();
+ for (int i = 0; i < cs.getSize(); ++i) {
+ string name = cs.get(i).getName() + "_control";
+ CoordinateActuator* actuator = NULL;
+ if (model.getForceSet().contains(name)) {
+ actuator = (CoordinateActuator*)&model.getForceSet().get(name);
+ } else {
+ actuator = new CoordinateActuator();
+ actuator->setCoordinate(&cs.get(i));
+ actuator->setName(name);
+ // since this object is creating these actuators for its own
+ // devices, it should take ownership of them, so that when the
+ // controller is removed, so are all the actuators it added
+ adoptSubcomponent(actuator);
+ }
+
+ actuator->setOptimalForce(1.0);
+ updActuators().adoptAndAppend(actuator);
+ log_debug("added actuator: {}", actuator->getName());
+ // append labels
+ storageLabels.append(cs[i].getName());
+ }
+ // configure Storage
+ appliedForces.setColumnLabels(storageLabels);
+ appliedForces.reset(0);
+
+ _tau.resize(cs.getSize());
+ _tau.setTo(0.0);
+
+ n = getModel().getNumCoordinates();
+}
+
+void TaskSpaceTorqueController::extendAddToSystem( SimTK::MultibodySystem& system) const
+{
+ Super::extendAddToSystem(system);
+
+ // add event handler for updating controls for next window
+ TaskSpaceTorqueController* mutableThis = const_cast(this);
+ ComputeControlsEventHandler* computeControlsHandler =
+ new ComputeControlsEventHandler(mutableThis);
+
+ computeControlsHandler->setEventInterval(0.01);
+
+ system.updDefaultSubsystem().addEventHandler(computeControlsHandler );
+}
+
+/**
+ * Set the requested integrator time step size.
+ *
+ * @param aDT Step size (0.0 <= aDT).
+ */
+void TaskSpaceTorqueController::
+setDT(double aDT)
+{
+ _dt = aDT;
+ if(_dt<0) _dt=0.0;
+}
+//_____________________________________________________________________________
+/**
+ * Get the requested integrator time step size.
+ *
+ * @return Step size.
+ */
+double TaskSpaceTorqueController::
+getDT() const
+{
+ return(_dt);
+}
+
+//-----------------------------------------------------------------------------
+// TARGET TIME
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Set the target time (or final time) for the controller.
+ *
+ * The function of the controller is to compute a set of controls that
+ * are appropriate from the current time in a simulation to the
+ * target time of the controller. If an integrator is taking time steps
+ * prior to the target time, the controls should not have to be computed again.
+ *
+ * @param aTargetTime Time in the future for which the controls have been
+ * computed.
+ * @see getCheckTargetTime()
+ */
+void TaskSpaceTorqueController::
+setTargetTime(double aTargetTime)
+{
+ _tf = aTargetTime;
+}
+//_____________________________________________________________________________
+/**
+ * Get the target time.
+ *
+ * The target time is the time in the future for which the controls have been
+ * calculated. If an integrator is taking time steps prior to the target
+ * time, the controls should not have to be computed again.
+ *
+ * @return Time in the future for which the controls have been
+ * computed.
+ * @see getCheckTargetTime()
+ */
+double TaskSpaceTorqueController::
+getTargetTime() const
+{
+ return(_tf);
+}
+
+//-----------------------------------------------------------------------------
+// TARGET DT
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Set the target time step size.
+ *
+ * The target time step size is the step size used to compute a new target
+ * time, once the former target time has been reached by the integrator.
+ *
+ * @param aDT Target time step size. Must be greater than 1.0e-8.
+ * @see setTargetTime()
+ */
+void TaskSpaceTorqueController::
+setTargetDT(double aDT)
+{
+ _targetDT = aDT;
+ if(_targetDT<1.0e-8) _targetDT = 1.0e-8;
+}
+//_____________________________________________________________________________
+/**
+ * Get the target time step size.
+ *
+ * The target time step size is the step size used to compute a new target
+ * time, once the former target time has been reached by the integrator.
+ *
+ * @return Target time step size.
+ * @see setTargetTime()
+ */
+double TaskSpaceTorqueController::
+getTargetDT() const
+{
+ return(_targetDT);
+}
+
+//-----------------------------------------------------------------------------
+// CHECK TARGET TIME
+//-----------------------------------------------------------------------------
+//_____________________________________________________________________________
+/**
+ * Set whether or not to check the target time.
+ *
+ * @param aTrueFalse If true, the target time will be checked. If false, the
+ * target time will not be checked.
+ * @see setTargetTime()
+ */
+void TaskSpaceTorqueController::
+setCheckTargetTime(bool aTrueFalse)
+{
+ _checkTargetTime = aTrueFalse;
+}
+//_____________________________________________________________________________
+/**
+ * Get whether or not to check the target time.
+ *
+ * @return True if the target time will be checked. False if the target
+ * time will not be checked.
+ * @see setTargetTime()
+ */
+bool TaskSpaceTorqueController::
+getCheckTargetTime() const
+{
+ return(_checkTargetTime);
+}
diff --git a/OpenSim/Tools/TaskSpaceTorqueController.h b/OpenSim/Tools/TaskSpaceTorqueController.h
new file mode 100644
index 0000000000..4d25add7b0
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceTorqueController.h
@@ -0,0 +1,191 @@
+#ifndef OPENSIM_TASK_SPACE_TORQUE_CONTROLLER_H_
+#define OPENSIM_TASK_SPACE_TORQUE_CONTROLLER_H_
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceTorqueController.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * and Dimitar Stanev *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "OpenSim/Simulation/Control/Controller.h"
+
+#include "TaskSpaceTaskSet.h"
+#include "TaskSpaceConstraintModel.h"
+
+namespace OpenSim {
+/**
+ * \brief Computes and applies the generalized forces that track the task
+ * goals provided a function for evaluating the control strategy.
+ *
+ * As this is a generalized force controller that evaluates the control
+ * strategy and applies the forces to the model. As this is a Controller
+ * and not a Force, CoordinateActuators are appended to the model and
+ * actuated according to the control strategy.
+ */
+
+class ConstraintProjection;
+
+class OSIMTOOLS_API TaskSpaceTorqueController : public Controller {
+ OpenSim_DECLARE_CONCRETE_OBJECT(TaskSpaceTorqueController, Controller);
+
+public:
+//==============================================================================
+// PROPERTIES
+//==============================================================================
+ OpenSim_DECLARE_UNNAMED_PROPERTY(TaskSpaceTaskSet,
+ "Set of tracking goals in task space.");
+
+ OpenSim_DECLARE_UNNAMED_PROPERTY(ConstraintModel,
+ "Name of the constraint model to use.");
+
+ OpenSim_DECLARE_LIST_PROPERTY(excluded_coords, std::string,
+ "List of coordinates that are not actuated.");
+
+ OpenSim_DECLARE_PROPERTY(control_strategy, std::string,
+ "Type of feedback control strategy to implement.");
+
+ OpenSim_DECLARE_PROPERTY(use_constraint_nullspace, bool,
+ "If true, constraints are given priority -1.");
+
+//=============================================================================
+// METHODS
+//=============================================================================
+public:
+ //CONSTRUCTION
+ TaskSpaceTorqueController();
+ TaskSpaceTorqueController(const TaskSpaceTorqueController& aController);
+
+ /**
+ * Prints the applied forces to a .sto file format.
+ *
+ * @param aPrefix is added to the file (useful for batch simulations).
+ * @param aDir is the directory where the results will be stored.
+ */
+ void printResults(const std::string &aPrefix, const std::string &aDir);
+
+ /** Controller. */
+ void computeControls(
+ const SimTK::State& s, SimTK::Vector& controls) const override;
+
+ SimTK::Vector _tau;
+
+ void setDT(double aDT);
+ double getDT() const;
+ void setTargetTime(double aTime);
+ double getTargetTime() const;
+ void setTargetDT(double aDT);
+ double getTargetDT() const;
+ void setCheckTargetTime(bool aTrueFalse);
+ bool getCheckTargetTime() const;
+
+protected:
+
+ /** Compute the generalized forces tau needed to control the model. */
+ SimTK::Vector calcTau(const SimTK::State& s) const;
+
+ void extendFinalizeFromProperties() override;
+
+ //TODO: not needed?
+ // for adding any components to the underlying system
+ void extendAddToSystem( SimTK::MultibodySystem& system) const override;
+
+ void extendConnectToModel(Model& model) override;
+
+ /** Selection matrix \f$ \tau^{'} = B \tau \f$ for under-actuation. */
+ mutable SimTK::Matrix B;
+
+ /* Current priority level being evaluated. */
+ int max_priority = 0;
+
+ /* Number of generalized coordinates. */
+ int n = 0;
+
+ /* Selected constraint projection method. */
+ //ConstraintProjection* m_constraint_projection;
+
+ /* Priority-sorted augmented Jacobian matrix. */
+ std::vector Jt_p;
+
+ // Priority-sorted desired accelerations
+ std::vector xtddot_p;
+
+ // Priority-sorted task bias
+ std::vector bt_p;
+
+ /** Stores the applied generalized forces. */
+ mutable Storage appliedForces;
+
+ /** Next integration step size that is to be taken by the integrator. */
+ double _dt;
+ /** Last integration step size that was taken before a new integration
+ step size was set in order to step exactly to the target time. */
+ double _lastDT;
+ /** Flag indicating when the last integration step size should be restored.
+ Normally it is restored only following a change to the integration
+ step size that was made to step exactly to the end of a target interval. */
+ bool _restoreDT;
+ /** The target time is the time in the future (in normalized units) for
+ which the controls have been calculated. If an integrator is taking
+ steps prior to the target time, the controls should not have to be
+ computed again. */
+ double _tf;
+
+ /** The step size used to generate a new target time, once the
+ old target time has been reached. */
+ double _targetDT;
+
+ /** Whether or not to check the target time. */
+ bool _checkTargetTime;
+
+private:
+
+ void constructProperties();
+ void setNull();
+ void copyData(const TaskSpaceTorqueController& aController);
+
+ /**
+ * @brief Create the selection matrix \f$ \tau^{'} = S \tau \f$ for
+ * under-actuation. Generates the matrix from the acuated_dofs property.
+ * This method is called automatically when the model is set using
+ * setModel(), but should be called again if the actuated_dofs are altered.
+ * Must be called during initialization.
+ *
+ * @param model
+ *
+ * \throws Exception if user-specified actuated DoFs do not match number of
+ * DoFs in model.
+ */
+ SimTK::Matrix createSelectionMatrix() const;
+
+//=============================================================================
+}; // END of class TaskSpaceTorqueController
+//=============================================================================
+//=============================================================================
+} // namespace OpenSim
+
+#endif
diff --git a/OpenSim/Tools/TaskSpaceUtilities.cpp b/OpenSim/Tools/TaskSpaceUtilities.cpp
new file mode 100644
index 0000000000..315a24bdf2
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceUtilities.cpp
@@ -0,0 +1,296 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceUtilities.cpp *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+
+#include "TaskSpaceUtilities.h"
+
+using namespace std;
+using namespace SimTK;
+
+namespace OpenSim {
+
+//================================================================================
+// CONVENIENCE FUNCTIONS
+//================================================================================
+
+/**
+ * @brief wraps SimbodyMatterSubsystems's calcM()
+ *
+ * @param s
+ * @param model
+ * @return Matrix
+ */
+Matrix calcM(const State& s, const Model& model) {
+ Matrix M;
+ model.getMatterSubsystem().calcM(s, M);
+ return M;
+}
+
+/**
+ * @brief return SVD inverse of M.
+ *
+ * @param s
+ * @param model
+ * @return Matrix
+ */
+Matrix calcMInv(const State& s, const Model& model) {
+ Matrix MInv, M;
+ model.getMatterSubsystem().calcM(s, M);
+ MInv = FactorSVDPseudoinverse(M);
+ return MInv;
+}
+
+/**
+ * @brief wraps SimbodyMatterSubsystem's calcFrameJacobian()
+ *
+ * @param s
+ * @param model
+ * @param b
+ * @param loc_in_B
+ * @return Matrix
+ */
+Matrix calcFrameJacobian(const State& s, const Model& model,
+ const SimTK::MobilizedBodyIndex& b, const Vec3& loc_in_B) {
+ SimTK::Matrix J;
+ model.getMultibodySystem().getMatterSubsystem().calcFrameJacobian(
+ s, b, loc_in_B, J);
+ return J;
+}
+
+/**
+ * This function calculates the total applied forces. In order to calculate them
+ * the model must be realized to Stage::Dynamics. This method is typically
+ * called in mixed dynamics scheme thus while the model is numerically
+ * integrated (forward dynamics) we may be interested in the acting forces so
+ * that a controller (e.g. inverse dynamics torque controller) can calculate the
+ * controls correctly. If however the original model is realized to
+ * Stage::Dynamics the controller's computeControls will be called again and
+ * this will cause an infinite loop. To avoid this problem upon first entrance
+ * to this function a working copy of the model is created without the
+ * controller and this working model is realized to Stage::Dynamics. Each time
+ * the working state is updated from the current state of the simulating model
+ * and the variables of the working model's working state.
+ */
+Vector calcTotalForces(const State& s, const Model& model) {
+ // create a working instance of the model, upon first entrance to this
+ // function
+ static Model* workingModel = NULL;
+ if (workingModel == NULL) {
+ workingModel = model.clone();
+ workingModel->setUseVisualizer(false);
+ // remove controllers to avoid infinite loop
+ workingModel->updControllerSet().setSize(0);
+ // disable any actuators when computing the total force
+ auto& fs = workingModel->updForceSet();
+ for (int i = 0; i < fs.getSize(); i++) {
+ auto pathActuator = dynamic_cast(&fs[i]);
+ if (pathActuator) {
+ pathActuator->set_appliesForce(false);
+ }
+ }
+ workingModel->finalizeFromProperties();
+ workingModel->initSystem();
+ }
+ // initialize working state from s
+ auto workingState = workingModel->updWorkingState();
+ workingState.setTime(s.getTime());
+ workingState.setQ(s.getQ());
+ workingState.setU(s.getU());
+ workingState.setZ(s.getZ());
+ workingState.setY(s.getY());
+ // generalized forces and torques should be accessed at a Dynamics stage
+ workingModel->realizeDynamics(workingState);
+ // get acting torques and body forces
+ auto bodyForces = workingModel->getMultibodySystem()
+ .getRigidBodyForces(workingState, Stage::Dynamics);
+ auto generalizedForces = workingModel->getMultibodySystem()
+ .getMobilityForces(workingState, Stage::Dynamics);
+ // map body forces to joint forces
+ Vector jointForces;
+ workingModel->getMatterSubsystem()
+ .multiplyBySystemJacobianTranspose(workingState, bodyForces, jointForces);
+ // in our convention we subtract their contribution
+ return -1.0 * generalizedForces - jointForces;
+}
+
+/**
+ * Calculates the Coriolis contribution \f$ \tau_c \f$. We assume that
+ * \f$ \tau_c \f$ is on the same side with the joint space accelerations
+ * (i.e. \f$ M \ddot{q} + \tau_c = \tau \f$).
+ */
+Vector calcCoriolis(const State& s, const Model& model) {
+ Vector c;
+ model.getMatterSubsystem().calcResidualForceIgnoringConstraints(
+ s, Vector(0), Vector_(0), Vector(0), c);
+ return c;
+}
+
+Vector calcTotalGeneralizedForces(const State& s, const Model& model) {
+ // compute all acting forces add Coriolis since they are not accounted
+ return calcCoriolis(s, model) + calcTotalForces(s, model);
+ // compute only Coriolis and gravity (works always)
+ // return calcCoriolis(s, model) + calcGravity(s, model);
+}
+
+//================================================================================
+// MATH UTILITIES
+//================================================================================
+
+Matrix concatenate(const Matrix &A, const Matrix &B, const int dim) {
+ if (A.nelt() == 0) { return B; }
+ if (B.nelt() == 0) { return A; }
+
+ Matrix C;
+ if (dim == 0) {
+ // Concatenate vertically
+ if (A.ncol() != B.ncol()) {
+ OPENSIM_THROW(
+ OpenSim::Exception,
+ "Matrices being concatenated must have same number of columns.")
+ }
+ C.resize(A.nrow() + B.nrow(), A.ncol());
+ C.updBlock(0, 0, A.nrow(), A.ncol()) = A;
+ C.updBlock(A.nrow(), 0, B.nrow(), B.ncol()) = B;
+ } else if (dim == 1) {
+ // Concatenate horizontally
+ if (A.nrow() != B.nrow()) {
+ OPENSIM_THROW(
+ OpenSim::Exception,
+ "Matrices being concatenated must have same number of rows.")
+ }
+ C.resize(A.nrow(), A.ncol() + B.ncol());
+ C.updBlock(0, 0, A.nrow(), A.ncol()) = A;
+ C.updBlock(0, A.ncol(), B.nrow(), B.ncol()) = B;
+ } else {
+ OPENSIM_THROW(OpenSim::Exception, "Dimension must be 0 or 1.")
+ }
+ return C;
+}
+
+/**
+ * \brief Convenience method for turning a spatial vec into a matrix
+ */
+Matrix FlattenSpatialVec(const SpatialVec& S) {
+ // turn a spatialvec into a 6x1 matrix.
+ Matrix spatialVecFlat(6, 1, 0.0);
+ spatialVecFlat[0] = S[0][0];
+ spatialVecFlat[1] = S[0][1];
+ spatialVecFlat[2] = S[0][2];
+ spatialVecFlat[3] = S[1][0];
+ spatialVecFlat[4] = S[1][1];
+ spatialVecFlat[5] = S[1][2];
+ return spatialVecFlat;
+}
+
+/**
+ * @brief SVD Pseudoinverse wrapped from Simbody FactorSVD.inverse()
+ *
+ * @param A
+ * @return Matrix
+ */
+Matrix FactorSVDPseudoinverse(const Matrix& A) {
+ Matrix Ainv;
+ FactorSVD AInvSVD(A);
+ try {
+ AInvSVD.inverse(Ainv);
+ } catch (...) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "SVD inverse failed because the matrix is rank deficient or "
+ "ill-conditioned, try with a different technique or check the "
+ "joint configuration if you are near a singular configuration "
+ "of the system.");
+ }
+ return Ainv;
+}
+
+/**
+ * @brief Selectively damped least-squares inverse with SVD based on the
+ * threshold tolerance defined in InverseDynamicsModel.cpp
+ *
+ * @param A
+ * @return Matrix
+ */
+Matrix DampedSVDPseudoinverse(const Matrix& A, const double& tolerance) {
+ Matrix Ainv;
+ Matrix U = Matrix();
+ Matrix VT = Matrix();
+ Vector S = Vector();
+ FactorSVD AInvSVD(A);
+ try {
+ AInvSVD.getSingularValuesAndVectors(S, U, VT);
+
+ auto dInv = S;
+ for (int k = 0; k < dInv.nrow(); ++k) {
+ if (S(k) < tolerance) {
+ dInv(k) = std::pow(tolerance, 2.0); // 0.0;
+ } else {
+ dInv(k) = 1 / S(k);
+ }
+ }
+ Matrix SInv = diagonalize(dInv);
+ Ainv = VT.transpose() * SInv * U.transpose();
+ } catch (...) {
+ OPENSIM_THROW(OpenSim::Exception,
+ "SVD inverse failed because the matrix is rank deficient or "
+ "ill-conditioned,",
+ " try with a different technique or check the joint "
+ "configuration if you are near a singular configuration of the "
+ "system.");
+ }
+ return Ainv;
+}
+
+/**
+ * @brief Construct a diagonal matrix from a vector
+ *
+ * @param A
+ * @return Matrix
+ */
+Matrix diagonalize(const Vector& A) {
+ Matrix B = Matrix(A.nrow(), A.nrow(), 0.0);
+ for (int i = 0; i < A.nelt(); ++i) { B(i, i) = A(i); }
+ return B;
+}
+
+/**
+ * @brief Create a block diagonal matrix.
+ *
+ * @param A
+ * @param B
+ * @return Matrix
+ */
+Matrix diagonalize(const Matrix& A, const Matrix& B) {
+ Matrix C(A.nrow() + B.nrow(), A.ncol() + B.ncol(), 0.0);
+ C.updBlock(0, 0, A.nrow(), A.ncol()) = A;
+ C.updBlock(A.nrow(), A.ncol(), B.nrow(), B.ncol()) = B;
+
+ return C;
+}
+} // namespace OpenSim
\ No newline at end of file
diff --git a/OpenSim/Tools/TaskSpaceUtilities.h b/OpenSim/Tools/TaskSpaceUtilities.h
new file mode 100644
index 0000000000..2c9c6dcf69
--- /dev/null
+++ b/OpenSim/Tools/TaskSpaceUtilities.h
@@ -0,0 +1,169 @@
+/* -------------------------------------------------------------------------- *
+ * OpenSim: TaskSpaceUtilities.h *
+ * -------------------------------------------------------------------------- *
+ * Developed by CFD Research Corporation for a project sponsored by the US *
+ * Army Medical Research and Materiel Command under Contract No. *
+ * W81XWH-22-C-0020. Any views, opinions and/or findings expressed in this *
+ * material are those of the author(s) and should not be construed as an *
+ * official Department of the Army position, policy or decision unless so *
+ * designated by other documentation. *
+ * *
+ * Please refer to the following publication for mathematical details, and *
+ * cite this paper if you use this code in your own work: *
+ * *
+ * Pickle and Sundararajan. "Predictive simulation of human movement in *
+ * OpenSim using floating-base task space control". *
+ * *
+ * Copyright (c) 2023 CFD Research Corporation and the Authors *
+ * *
+ * Author(s): Aravind Sundararajan, Nathan Pickle, Garrett Tuer *
+ * *
+ * Licensed under the Apache License, Version 2.0 (the "License"); you may *
+ * not use this file except in compliance with the License. You may obtain a *
+ * copy of the License at http://www.apache.org/licenses/LICENSE-2.0 *
+ * *
+ * Unless required by applicable law or agreed to in writing, software *
+ * distributed under the License is distributed on an "AS IS" BASIS, *
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. *
+ * See the License for the specific language governing permissions and *
+ * limitations under the License. *
+ * -------------------------------------------------------------------------- */
+#ifndef OPENSIM_TASK_SPACE_UTILITIES_H_
+#define OPENSIM_TASK_SPACE_UTILITIES_H_
+
+#include "simbody/internal/MobilizedBody.h"
+#include "OpenSim/Simulation/Model/Model.h"
+
+/**
+ * \brief Struct that holds matrices relevant to support consistent modeling
+ * such that each map value is keyed with the MobilizedBodyIndex of the
+ * supporting link.
+ *
+ */
+namespace OpenSim {
+
+//================================================================================
+// CONVENIENCE FUNCTIONS
+//================================================================================
+
+/**
+ * @brief wraps SimbodyMatterSubsystems's calcM()
+ *
+ * @param s
+ * @param model
+ * @return Matrix
+ */
+SimTK::Matrix calcM(
+ const SimTK::State& s, const OpenSim::Model& model);
+
+/**
+ * @brief return SVD inverse of M.
+ *
+ * @param s
+ * @param model
+ * @return Matrix
+ */
+SimTK::Matrix calcMInv(
+ const SimTK::State& s, const OpenSim::Model& model);
+
+/**
+ * @brief wraps SimbodyMatterSubsystem's calcFrameJacobian(). Used to compute
+ * components of Support Consistent Jacobian. For use with Support Model.
+ *
+ * @param s
+ * @param model
+ * @param b
+ * @param loc_in_B
+ * @return Matrix
+ */
+
+/**
+ * @brief wraps SimbodyMatterSubsystem's calcFrameJacobian(). Used to compute
+ * components of Support Consistent Jacobian. For use with Support Model.
+ *
+ * @param s
+ * @param model
+ * @param b
+ * @param loc_in_B
+ * @return Matrix
+ */
+SimTK::Matrix calcFrameJacobian(const SimTK::State& s,
+ const OpenSim::Model& model, const SimTK::MobilizedBodyIndex& b,
+ const SimTK::Vec3& loc_in_B);
+
+/**
+ * Calculates the total force that act on the model (\f$ f \f$). This requires
+ * that the model is realized to Stage::Dynamics. A working model is used as
+ * this method may be called by a controller during numerical integration and
+ * all controllers of the working model are removed to avoid infinite loops.
+ * The actuators of the working model are disabled since they are the actuation
+ * (i.e. muscles \f$ \tau = R f_m \f$ and not \f$ f \f$). Call this method only
+ * from objects that are derived from OpenSim::Controller and never from
+ * objects that are derived from OpenSim::Force.
+ */
+SimTK::Vector calcTotalGeneralizedForces(const SimTK::State& s,
+ const OpenSim::Model& model);
+
+
+//================================================================================
+// MATH UTILITIES
+//================================================================================
+
+/**
+ * SVD Pseudoinverse wrapped from Simbody FactorSVD.inverse()
+ *
+ * @param A
+ * @return Matrix
+ */
+SimTK::Matrix FactorSVDPseudoinverse(const SimTK::Matrix& A);
+
+/**
+ * @brief Selectively damped least-squares inverse with SVD based on the
+ * specified threshold tolerance.
+ *
+ * @param A
+ * @param tolerance
+ * @return Matrix
+ */
+SimTK::Matrix DampedSVDPseudoinverse(
+ const SimTK::Matrix& A,
+ const double& tolerance=std::numeric_limits::epsilon());
+
+/**
+ * \brief Convenience method for turning a 3x2 spatial vec into a 6x1 Matrix
+ */
+SimTK::Matrix FlattenSpatialVec(const SimTK::SpatialVec& S);
+
+/**
+ * @brief Concatenate 2 Matrices along the specified dimension dim.
+ *
+ * @param A
+ * @param B
+ * @param dim
+ * @return Matrix
+ */
+SimTK::Matrix concatenate(
+ const SimTK::Matrix& A, const SimTK::Matrix& B, const int dim);
+
+/**
+ * @brief Construct a diagonal matrix from a vector
+ *
+ * @param A
+ * @return Matrix
+ */
+SimTK::Matrix diagonalize(const SimTK::Vector& A);
+
+/**
+ * @brief Create a block diagonal matrix.
+ *
+ * @param A
+ * @param B
+ * @return Matrix
+ */
+SimTK::Matrix diagonalize(
+ const SimTK::Matrix& A, const SimTK::Matrix& B);
+
+
+
+} // namespace OpenSim
+#endif
diff --git a/OpenSim/Tools/TrackingTask.cpp b/OpenSim/Tools/TrackingTask.cpp
index 388cccd75f..7ae966a054 100644
--- a/OpenSim/Tools/TrackingTask.cpp
+++ b/OpenSim/Tools/TrackingTask.cpp
@@ -165,7 +165,7 @@ operator=(const TrackingTask &aTask)
* @param aModel Model.
*/
void TrackingTask::
-setModel(Model& aModel)
+setModel(const Model& aModel)
{
_model = &aModel;
}
@@ -176,7 +176,7 @@ setModel(Model& aModel)
*
* @return Pointer to the model.
*/
-Model* TrackingTask::
+const Model* TrackingTask::
getModel() const
{
return(_model);
diff --git a/OpenSim/Tools/TrackingTask.h b/OpenSim/Tools/TrackingTask.h
index 226d42f684..dda7872748 100644
--- a/OpenSim/Tools/TrackingTask.h
+++ b/OpenSim/Tools/TrackingTask.h
@@ -62,7 +62,7 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(TrackingTask, Object);
Array &_w;
/** Model. */
- Model *_model;
+ const Model *_model;
/** Number of functions for this target. */
int _nTrk;
@@ -108,8 +108,8 @@ OpenSim_DECLARE_ABSTRACT_OBJECT(TrackingTask, Object);
// GET AND SET
//--------------------------------------------------------------------------
// MODEL
- virtual void setModel(OpenSim::Model& aModel);
- Model* getModel() const;
+ virtual void setModel(const OpenSim::Model& aModel);
+ const Model* getModel() const;
// ON,OFF
void setOn(bool aTrueFalse);
diff --git a/OpenSim/Tools/osimTools.h b/OpenSim/Tools/osimTools.h
index 66b7c3b889..9bb27bac29 100644
--- a/OpenSim/Tools/osimTools.h
+++ b/OpenSim/Tools/osimTools.h
@@ -49,6 +49,17 @@
#include "SMC_Joint.h"
#include "CMC_TaskSet.h"
#include "CorrectionController.h"
+
+#include "TaskSpaceTorqueController.h"
+#include "TaskSpaceComputeControlsEventHandler.h"
+#include "TaskSpaceConstraintModel.h"
+#include "TaskSpaceTask.h"
+#include "TaskSpaceBodyTask.h"
+#include "TaskSpaceOrientationTask.h"
+#include "TaskSpaceStationTask.h"
+#include "TaskSpaceCoordinateTask.h"
+#include "TaskSpaceInertiaTask.h"
+
#include "RegisterTypes_osimTools.h" // to expose RegisterTypes_osimTools
#endif // OPENSIM_OSIMTOOLS_H_